Update Gazebo, add ROS bridging, and implement controller warmup.
This commit is contained in:
@@ -49,8 +49,10 @@ def generate_launch_description():
|
||||
executable='parameter_bridge',
|
||||
name='gz_bridge',
|
||||
arguments=[
|
||||
# Velocity commands (bidirectional)
|
||||
# Drone velocity commands (ROS to Gazebo)
|
||||
'/drone/cmd_vel@geometry_msgs/msg/Twist]ignition.msgs.Twist',
|
||||
# Rover velocity commands (ROS to Gazebo)
|
||||
'/rover/cmd_vel@geometry_msgs/msg/Twist]ignition.msgs.Twist',
|
||||
# Odometry (from Gazebo to ROS)
|
||||
'/model/drone/odometry@nav_msgs/msg/Odometry[ignition.msgs.Odometry',
|
||||
# IMU (from Gazebo to ROS)
|
||||
|
||||
@@ -1,7 +1,7 @@
|
||||
<?xml version="1.0" ?>
|
||||
<!--
|
||||
Drone Landing Simulation - Ignition Fortress World
|
||||
Compatible with ROS 2 Humble
|
||||
With velocity control for drone and rover
|
||||
-->
|
||||
<sdf version="1.8">
|
||||
<world name="drone_landing_world">
|
||||
@@ -62,11 +62,20 @@
|
||||
</link>
|
||||
</model>
|
||||
|
||||
<!-- Landing Pad (Rover) -->
|
||||
<!-- Landing Pad (Rover) - Now with velocity control -->
|
||||
<model name="landing_pad">
|
||||
<static>true</static>
|
||||
<pose>0 0 0.15 0 0 0</pose>
|
||||
|
||||
<link name="base_link">
|
||||
<inertial>
|
||||
<mass>10.0</mass>
|
||||
<inertia>
|
||||
<ixx>1.0</ixx><ixy>0</ixy><ixz>0</ixz>
|
||||
<iyy>1.0</iyy><iyz>0</iyz>
|
||||
<izz>1.0</izz>
|
||||
</inertia>
|
||||
</inertial>
|
||||
|
||||
<visual name="visual">
|
||||
<geometry>
|
||||
<box><size>1.0 1.0 0.3</size></box>
|
||||
@@ -81,6 +90,7 @@
|
||||
<box><size>1.0 1.0 0.3</size></box>
|
||||
</geometry>
|
||||
</collision>
|
||||
|
||||
<!-- H marker -->
|
||||
<visual name="h_center">
|
||||
<pose>0 0 0.151 0 0 0</pose>
|
||||
@@ -107,11 +117,26 @@
|
||||
</material>
|
||||
</visual>
|
||||
</link>
|
||||
|
||||
<!-- Rover velocity control - subscribes to /rover/cmd_vel -->
|
||||
<plugin filename="libignition-gazebo-velocity-control-system.so"
|
||||
name="ignition::gazebo::systems::VelocityControl">
|
||||
<topic>/rover/cmd_vel</topic>
|
||||
<initial_linear>0 0 0</initial_linear>
|
||||
</plugin>
|
||||
|
||||
<!-- Keep rover on ground -->
|
||||
<plugin filename="libignition-gazebo-planar-move-system.so"
|
||||
name="ignition::gazebo::systems::PlanarMove">
|
||||
<cmd_topic>/rover/cmd_vel</cmd_topic>
|
||||
<odom_topic>/rover/odom</odom_topic>
|
||||
</plugin>
|
||||
|
||||
</model>
|
||||
|
||||
<!-- Drone -->
|
||||
<!-- Drone with velocity control -->
|
||||
<model name="drone">
|
||||
<pose>0 0 5 0 0 0</pose>
|
||||
<pose>0 0 2 0 0 0</pose>
|
||||
|
||||
<link name="base_link">
|
||||
<inertial>
|
||||
@@ -187,6 +212,13 @@
|
||||
</sensor>
|
||||
</link>
|
||||
|
||||
<!-- Drone velocity control - subscribes to /drone/cmd_vel -->
|
||||
<plugin filename="libignition-gazebo-velocity-control-system.so"
|
||||
name="ignition::gazebo::systems::VelocityControl">
|
||||
<topic>/drone/cmd_vel</topic>
|
||||
<initial_linear>0 0 0</initial_linear>
|
||||
</plugin>
|
||||
|
||||
<!-- Odometry Publisher -->
|
||||
<plugin filename="libignition-gazebo-odometry-publisher-system.so"
|
||||
name="ignition::gazebo::systems::OdometryPublisher">
|
||||
|
||||
Reference in New Issue
Block a user