Files
RDC_Simulation/gazebo/worlds/drone_landing.sdf

235 lines
7.9 KiB
XML

<?xml version="1.0" ?>
<!--
Drone Landing Simulation - Ignition Fortress World
With velocity control for drone and rover
-->
<sdf version="1.8">
<world name="drone_landing_world">
<!-- Physics -->
<physics name="1ms" type="ode">
<max_step_size>0.001</max_step_size>
<real_time_factor>1.0</real_time_factor>
</physics>
<!-- Ignition Fortress Plugins -->
<plugin filename="libignition-gazebo-physics-system.so"
name="ignition::gazebo::systems::Physics"/>
<plugin filename="libignition-gazebo-user-commands-system.so"
name="ignition::gazebo::systems::UserCommands"/>
<plugin filename="libignition-gazebo-scene-broadcaster-system.so"
name="ignition::gazebo::systems::SceneBroadcaster"/>
<plugin filename="libignition-gazebo-sensors-system.so"
name="ignition::gazebo::systems::Sensors">
<render_engine>ogre2</render_engine>
</plugin>
<plugin filename="libignition-gazebo-imu-system.so"
name="ignition::gazebo::systems::Imu"/>
<!-- Lighting -->
<light type="directional" name="sun">
<cast_shadows>true</cast_shadows>
<pose>0 0 10 0 0 0</pose>
<diffuse>0.8 0.8 0.8 1</diffuse>
<specular>0.2 0.2 0.2 1</specular>
<direction>-0.5 0.1 -0.9</direction>
</light>
<!-- Ground Plane -->
<model name="ground_plane">
<static>true</static>
<link name="link">
<collision name="collision">
<geometry>
<plane>
<normal>0 0 1</normal>
<size>100 100</size>
</plane>
</geometry>
</collision>
<visual name="visual">
<geometry>
<plane>
<normal>0 0 1</normal>
<size>100 100</size>
</plane>
</geometry>
<material>
<ambient>0.5 0.5 0.5 1</ambient>
<diffuse>0.7 0.7 0.7 1</diffuse>
</material>
</visual>
</link>
</model>
<!-- Landing Pad (Rover) - Now with velocity control -->
<model name="landing_pad">
<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>
</geometry>
<material>
<ambient>0.1 0.5 0.1 1</ambient>
<diffuse>0.2 0.7 0.2 1</diffuse>
</material>
</visual>
<collision name="collision">
<geometry>
<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>
<geometry><box><size>0.6 0.1 0.001</size></box></geometry>
<material>
<ambient>1 1 1 1</ambient>
<diffuse>1 1 1 1</diffuse>
</material>
</visual>
<visual name="h_left">
<pose>-0.25 0 0.151 0 0 0</pose>
<geometry><box><size>0.1 0.5 0.001</size></box></geometry>
<material>
<ambient>1 1 1 1</ambient>
<diffuse>1 1 1 1</diffuse>
</material>
</visual>
<visual name="h_right">
<pose>0.25 0 0.151 0 0 0</pose>
<geometry><box><size>0.1 0.5 0.001</size></box></geometry>
<material>
<ambient>1 1 1 1</ambient>
<diffuse>1 1 1 1</diffuse>
</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 with velocity control -->
<model name="drone">
<pose>0 0 2 0 0 0</pose>
<link name="base_link">
<inertial>
<mass>1.0</mass>
<inertia>
<ixx>0.029</ixx><ixy>0</ixy><ixz>0</ixz>
<iyy>0.029</iyy><iyz>0</iyz>
<izz>0.055</izz>
</inertia>
</inertial>
<collision name="collision">
<geometry><box><size>0.3 0.3 0.1</size></box></geometry>
</collision>
<visual name="body">
<geometry><box><size>0.3 0.3 0.1</size></box></geometry>
<material>
<ambient>0.8 0.1 0.1 1</ambient>
<diffuse>0.9 0.2 0.2 1</diffuse>
</material>
</visual>
<!-- Arms -->
<visual name="arm_fl">
<pose>0.12 0.12 0 0 0 0.785</pose>
<geometry><box><size>0.2 0.02 0.02</size></box></geometry>
<material><diffuse>0.3 0.3 0.3 1</diffuse></material>
</visual>
<visual name="arm_fr">
<pose>0.12 -0.12 0 0 0 -0.785</pose>
<geometry><box><size>0.2 0.02 0.02</size></box></geometry>
<material><diffuse>0.3 0.3 0.3 1</diffuse></material>
</visual>
<visual name="arm_bl">
<pose>-0.12 0.12 0 0 0 -0.785</pose>
<geometry><box><size>0.2 0.02 0.02</size></box></geometry>
<material><diffuse>0.3 0.3 0.3 1</diffuse></material>
</visual>
<visual name="arm_br">
<pose>-0.12 -0.12 0 0 0 0.785</pose>
<geometry><box><size>0.2 0.02 0.02</size></box></geometry>
<material><diffuse>0.3 0.3 0.3 1</diffuse></material>
</visual>
<!-- Rotors -->
<visual name="rotor_fl">
<pose>0.17 0.17 0.05 0 0 0</pose>
<geometry><cylinder><radius>0.08</radius><length>0.01</length></cylinder></geometry>
<material><diffuse>0.2 0.2 0.2 1</diffuse></material>
</visual>
<visual name="rotor_fr">
<pose>0.17 -0.17 0.05 0 0 0</pose>
<geometry><cylinder><radius>0.08</radius><length>0.01</length></cylinder></geometry>
<material><diffuse>0.2 0.2 0.2 1</diffuse></material>
</visual>
<visual name="rotor_bl">
<pose>-0.17 0.17 0.05 0 0 0</pose>
<geometry><cylinder><radius>0.08</radius><length>0.01</length></cylinder></geometry>
<material><diffuse>0.2 0.2 0.2 1</diffuse></material>
</visual>
<visual name="rotor_br">
<pose>-0.17 -0.17 0.05 0 0 0</pose>
<geometry><cylinder><radius>0.08</radius><length>0.01</length></cylinder></geometry>
<material><diffuse>0.2 0.2 0.2 1</diffuse></material>
</visual>
<!-- IMU -->
<sensor name="imu" type="imu">
<always_on>true</always_on>
<update_rate>100</update_rate>
<topic>/drone/imu</topic>
</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">
<odom_frame>odom</odom_frame>
<robot_base_frame>base_link</robot_base_frame>
<odom_topic>/model/drone/odometry</odom_topic>
<odom_publish_frequency>50</odom_publish_frequency>
</plugin>
</model>
</world>
</sdf>