Gazebo Bridge Rover Update

This commit is contained in:
2026-01-02 06:41:11 +00:00
parent de156dfbdb
commit 1bbd9c8377
3 changed files with 99 additions and 12 deletions

View File

@@ -1,10 +1,10 @@
<?xml version="1.0" ?>
<!--
Drone Landing Competition - Gazebo World
Drone Landing Simulation - Gazebo World
This world contains:
- Ground plane with grid texture
- Landing pad (rover) at origin
- Landing pad (rover) at origin - can be moved via pose commands
- Drone spawned at 5m altitude
- Sun for lighting
-->
@@ -18,13 +18,13 @@
</physics>
<!-- Required plugins -->
<plugin filename="gz-sim-physics-system" name="gz::sim::systems::Physics"/>
<plugin filename="gz-sim-user-commands-system" name="gz::sim::systems::UserCommands"/>
<plugin filename="gz-sim-scene-broadcaster-system" name="gz::sim::systems::SceneBroadcaster"/>
<plugin filename="gz-sim-sensors-system" name="gz::sim::systems::Sensors">
<plugin filename="ignition-gazebo-physics-system" name="ignition::gazebo::systems::Physics"/>
<plugin filename="ignition-gazebo-user-commands-system" name="ignition::gazebo::systems::UserCommands"/>
<plugin filename="ignition-gazebo-scene-broadcaster-system" name="ignition::gazebo::systems::SceneBroadcaster"/>
<plugin filename="ignition-gazebo-sensors-system" name="ignition::gazebo::systems::Sensors">
<render_engine>ogre2</render_engine>
</plugin>
<plugin filename="gz-sim-imu-system" name="gz::sim::systems::Imu"/>
<plugin filename="ignition-gazebo-imu-system" name="ignition::gazebo::systems::Imu"/>
<!-- Lighting -->
<light type="directional" name="sun">
@@ -69,11 +69,28 @@
</link>
</model>
<!-- Landing Pad (Rover) -->
<!-- Landing Pad (Rover) - Non-static so it can be moved -->
<model name="landing_pad">
<static>true</static>
<static>false</static>
<pose>0 0 0.15 0 0 0</pose>
<!-- Pose publisher to track position -->
<plugin filename="ignition-gazebo-pose-publisher-system" name="ignition::gazebo::systems::PosePublisher">
<publish_link_pose>false</publish_link_pose>
<publish_model_pose>true</publish_model_pose>
<publish_nested_model_pose>false</publish_nested_model_pose>
<update_frequency>50</update_frequency>
</plugin>
<link name="base_link">
<inertial>
<mass>100.0</mass>
<inertia>
<ixx>10.0</ixx>
<iyy>10.0</iyy>
<izz>10.0</izz>
</inertia>
</inertial>
<collision name="collision">
<geometry>
<box>