Gazebo World Model Update

This commit is contained in:
2026-01-02 07:13:39 +00:00
parent 93fe686fab
commit 9450f286a1
3 changed files with 321 additions and 89 deletions

View File

@@ -1,110 +1,62 @@
#!/usr/bin/env python3 #!/usr/bin/env python3
""" """
Gazebo Launch File - Drone Landing Simulation Gazebo Launch File - Drone Landing Simulation
Launches Gazebo with the world and spawns the drone. Works with Ignition Fortress (ROS 2 Humble)
Supports both 'gz' (newer) and 'ign' (Fortress) commands.
""" """
import os import os
import shutil import shutil
from ament_index_python.packages import get_package_share_directory
from launch import LaunchDescription from launch import LaunchDescription
from launch.actions import DeclareLaunchArgument, ExecuteProcess, IncludeLaunchDescription from launch.actions import DeclareLaunchArgument, ExecuteProcess
from launch.conditions import IfCondition from launch.substitutions import LaunchConfiguration
from launch.launch_description_sources import PythonLaunchDescriptionSource
from launch.substitutions import LaunchConfiguration, PathJoinSubstitution
from launch_ros.actions import Node from launch_ros.actions import Node
def get_gazebo_command():
"""Determine whether to use 'gz' or 'ign' command."""
if shutil.which('gz'):
return 'gz'
elif shutil.which('ign'):
return 'ign'
else:
# Default to gz, will fail with helpful error
return 'gz'
def generate_launch_description(): def generate_launch_description():
"""Generate the launch description.""" """Generate the launch description."""
# Get paths
script_dir = os.path.dirname(os.path.abspath(__file__)) script_dir = os.path.dirname(os.path.abspath(__file__))
gazebo_dir = os.path.dirname(script_dir) gazebo_dir = os.path.dirname(script_dir)
world_file = os.path.join(gazebo_dir, 'worlds', 'drone_landing.sdf') world_file = os.path.join(gazebo_dir, 'worlds', 'drone_landing.sdf')
model_path = os.path.join(gazebo_dir, 'models')
drone_model = os.path.join(model_path, 'drone', 'model.sdf')
gz_resource_path = os.environ.get('GZ_SIM_RESOURCE_PATH', '') # Determine which gazebo command is available
ign_resource_path = os.environ.get('IGN_GAZEBO_RESOURCE_PATH', '') if shutil.which('ign'):
combined_path = f"{model_path}:{gz_resource_path}:{ign_resource_path}" gz_cmd = ['ign', 'gazebo', '-r', world_file]
elif shutil.which('gz'):
os.environ['GZ_SIM_RESOURCE_PATH'] = combined_path gz_cmd = ['gz', 'sim', '-r', world_file]
os.environ['IGN_GAZEBO_RESOURCE_PATH'] = combined_path else:
gz_cmd = ['ign', 'gazebo', '-r', world_file]
use_sim_time = LaunchConfiguration('use_sim_time', default='true') use_sim_time = LaunchConfiguration('use_sim_time', default='true')
headless = LaunchConfiguration('headless', default='false')
# Detect which Gazebo command is available
gz_cmd = get_gazebo_command()
# For ign command, use 'gazebo' subcommand; for gz, use 'sim'
if gz_cmd == 'ign':
sim_cmd = [gz_cmd, 'gazebo', '-r', world_file]
spawn_cmd = [
gz_cmd, 'service', '-s', '/world/drone_landing_world/create',
'--reqtype', 'ignition.msgs.EntityFactory',
'--reptype', 'ignition.msgs.Boolean',
'--timeout', '5000',
'--req', f'sdf_filename: "{drone_model}", name: "drone"'
]
else:
sim_cmd = [gz_cmd, 'sim', '-r', world_file]
spawn_cmd = [
gz_cmd, 'service', '-s', '/world/drone_landing_world/create',
'--reqtype', 'gz.msgs.EntityFactory',
'--reptype', 'gz.msgs.Boolean',
'--timeout', '5000',
'--req', f'sdf_filename: "{drone_model}", name: "drone"'
]
return LaunchDescription([ return LaunchDescription([
DeclareLaunchArgument( DeclareLaunchArgument(
'use_sim_time', 'use_sim_time',
default_value='true', default_value='true',
description='Use simulation (Gazebo) clock' description='Use simulation clock'
),
DeclareLaunchArgument(
'headless',
default_value='false',
description='Run Gazebo in headless mode (no GUI)'
), ),
# Start Gazebo
ExecuteProcess( ExecuteProcess(
cmd=sim_cmd, cmd=gz_cmd,
output='screen',
additional_env={
'GZ_SIM_RESOURCE_PATH': combined_path,
'IGN_GAZEBO_RESOURCE_PATH': combined_path
}
),
ExecuteProcess(
cmd=spawn_cmd,
output='screen' output='screen'
), ),
# ROS-Gazebo Bridge
Node( Node(
package='ros_gz_bridge', package='ros_gz_bridge',
executable='parameter_bridge', executable='parameter_bridge',
name='gz_bridge', name='gz_bridge',
arguments=[ arguments=[
'/drone/cmd_vel@geometry_msgs/msg/Twist@gz.msgs.Twist', # Velocity commands (bidirectional)
'/model/drone/odometry@nav_msgs/msg/Odometry@gz.msgs.Odometry', '/drone/cmd_vel@geometry_msgs/msg/Twist]ignition.msgs.Twist',
'/drone/imu@sensor_msgs/msg/Imu@gz.msgs.IMU', # Odometry (from Gazebo to ROS)
'/clock@rosgraph_msgs/msg/Clock@gz.msgs.Clock', '/model/drone/odometry@nav_msgs/msg/Odometry[ignition.msgs.Odometry',
# IMU (from Gazebo to ROS)
'/drone/imu@sensor_msgs/msg/Imu[ignition.msgs.IMU',
# Clock
'/clock@rosgraph_msgs/msg/Clock[ignition.msgs.Clock',
], ],
parameters=[{'use_sim_time': use_sim_time}], parameters=[{'use_sim_time': use_sim_time}],
output='screen' output='screen'
@@ -119,12 +71,9 @@ if __name__ == '__main__':
print(" ros2 launch gazebo/launch/drone_landing.launch.py") print(" ros2 launch gazebo/launch/drone_landing.launch.py")
print() print()
print("Or start Gazebo manually:") print("Or start Gazebo manually:")
if shutil.which('ign'):
gz_cmd = get_gazebo_command()
if gz_cmd == 'ign':
print(" ign gazebo gazebo/worlds/drone_landing.sdf") print(" ign gazebo gazebo/worlds/drone_landing.sdf")
else: else:
print(" gz sim gazebo/worlds/drone_landing.sdf") print(" gz sim gazebo/worlds/drone_landing.sdf")
print() print()
print("Then run: python run_gazebo.py") print("Then run: python run_gazebo.py")

View File

@@ -0,0 +1,161 @@
<?xml version="1.0" ?>
<!--
Simple Drone Model for Ignition Fortress
Uses velocity control for simple simulation
-->
<sdf version="1.8">
<model name="drone">
<pose>0 0 5 0 0 0</pose>
<!-- Main body -->
<link name="base_link">
<inertial>
<mass>1.0</mass>
<inertia>
<ixx>0.029125</ixx>
<ixy>0</ixy>
<ixz>0</ixz>
<iyy>0.029125</iyy>
<iyz>0</iyz>
<izz>0.055225</izz>
</inertia>
</inertial>
<collision name="body_collision">
<geometry>
<box>
<size>0.3 0.3 0.1</size>
</box>
</geometry>
</collision>
<visual name="body_visual">
<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>
<specular>0.2 0.2 0.2 1</specular>
</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>
<ambient>0.2 0.2 0.2 1</ambient>
<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>
<ambient>0.2 0.2 0.2 1</ambient>
<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>
<ambient>0.2 0.2 0.2 1</ambient>
<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>
<ambient>0.2 0.2 0.2 1</ambient>
<diffuse>0.3 0.3 0.3 1</diffuse>
</material>
</visual>
<!-- Rotors (visual only) -->
<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>
<ambient>0.1 0.1 0.1 1</ambient>
<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>
<ambient>0.1 0.1 0.1 1</ambient>
<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>
<ambient>0.1 0.1 0.1 1</ambient>
<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>
<ambient>0.1 0.1 0.1 1</ambient>
<diffuse>0.2 0.2 0.2 1</diffuse>
</material>
</visual>
<!-- IMU Sensor -->
<sensor name="imu_sensor" type="imu">
<always_on>true</always_on>
<update_rate>100</update_rate>
<topic>/drone/imu</topic>
</sensor>
</link>
<!-- Ignition Fortress compatible plugins -->
<!-- Apply velocity from /drone/cmd_vel topic -->
<plugin filename="libignition-gazebo-apply-link-wrench-system.so"
name="ignition::gazebo::systems::ApplyLinkWrench"/>
<!-- 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>
<!-- Pose Publisher -->
<plugin filename="libignition-gazebo-pose-publisher-system.so"
name="ignition::gazebo::systems::PosePublisher">
<publish_model_pose>true</publish_model_pose>
<publish_link_pose>false</publish_link_pose>
<update_frequency>50</update_frequency>
</plugin>
</model>
</sdf>

View File

@@ -1,20 +1,32 @@
<?xml version="1.0" ?> <?xml version="1.0" ?>
<!-- <!--
Drone Landing Simulation - Gazebo World (Ignition Fortress compatible) Drone Landing Simulation - Ignition Fortress World
Compatible with ROS 2 Humble
--> -->
<sdf version="1.8"> <sdf version="1.8">
<world name="drone_landing_world"> <world name="drone_landing_world">
<physics name="1ms" type="ignored"> <!-- Physics -->
<physics name="1ms" type="ode">
<max_step_size>0.001</max_step_size> <max_step_size>0.001</max_step_size>
<real_time_factor>1.0</real_time_factor> <real_time_factor>1.0</real_time_factor>
</physics> </physics>
<!-- Ignition Fortress plugins --> <!-- Ignition Fortress Plugins -->
<plugin filename="libignition-gazebo-physics-system.so" name="ignition::gazebo::systems::Physics"/> <plugin filename="libignition-gazebo-physics-system.so"
<plugin filename="libignition-gazebo-user-commands-system.so" name="ignition::gazebo::systems::UserCommands"/> name="ignition::gazebo::systems::Physics"/>
<plugin filename="libignition-gazebo-scene-broadcaster-system.so" name="ignition::gazebo::systems::SceneBroadcaster"/> <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"> <light type="directional" name="sun">
<cast_shadows>true</cast_shadows> <cast_shadows>true</cast_shadows>
<pose>0 0 10 0 0 0</pose> <pose>0 0 10 0 0 0</pose>
@@ -23,7 +35,7 @@
<direction>-0.5 0.1 -0.9</direction> <direction>-0.5 0.1 -0.9</direction>
</light> </light>
<!-- Ground --> <!-- Ground Plane -->
<model name="ground_plane"> <model name="ground_plane">
<static>true</static> <static>true</static>
<link name="link"> <link name="link">
@@ -50,16 +62,14 @@
</link> </link>
</model> </model>
<!-- Landing Pad (static for now) --> <!-- Landing Pad (Rover) -->
<model name="landing_pad"> <model name="landing_pad">
<static>true</static> <static>true</static>
<pose>0 0 0.15 0 0 0</pose> <pose>0 0 0.15 0 0 0</pose>
<link name="base_link"> <link name="base_link">
<visual name="visual"> <visual name="visual">
<geometry> <geometry>
<box> <box><size>1.0 1.0 0.3</size></box>
<size>1.0 1.0 0.3</size>
</box>
</geometry> </geometry>
<material> <material>
<ambient>0.1 0.5 0.1 1</ambient> <ambient>0.1 0.5 0.1 1</ambient>
@@ -68,13 +78,125 @@
</visual> </visual>
<collision name="collision"> <collision name="collision">
<geometry> <geometry>
<box> <box><size>1.0 1.0 0.3</size></box>
<size>1.0 1.0 0.3</size>
</box>
</geometry> </geometry>
</collision> </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> </link>
</model> </model>
<!-- Drone -->
<model name="drone">
<pose>0 0 5 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>
<!-- 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> </world>
</sdf> </sdf>