66from ament_index_python .packages import get_package_share_directory
77from launch import LaunchDescription
88from launch .launch_description_sources import PythonLaunchDescriptionSource
9- from launch .substitutions import LaunchConfiguration , Command , PythonExpression
9+ from launch .substitutions import LaunchConfiguration , Command , PythonExpression , PathJoinSubstitution
1010from launch .actions import DeclareLaunchArgument , IncludeLaunchDescription , AppendEnvironmentVariable
1111from launch .conditions import IfCondition
1212from launch_ros .actions import Node
13+ from launch_ros .substitutions import FindPackageShare
1314
1415
1516def generate_launch_description ():
1617 """
1718 Launch Function
1819 """
20+ pkg_dir = get_package_share_directory ('atreus' )
1921
20- # .................. Configurable Arguments .....................
21-
22- use_sim_time = True
23- gui = False
22+ rviz_config_path = os .path .join (
23+ pkg_dir , 'config' , 'rviz' , 'urdf.rviz' )
24+ world_path = os .path .join (pkg_dir , 'worlds' , 'mapping.sdf' )
25+ bridge_params_path = os .path .join (
26+ pkg_dir , 'config' , 'ros_gz_bridge.yaml'
27+ )
2428
25- world_name = 'mapping.sdf'
26- camera_enabled = False
27- two_d_lidar_enabled = False
28- rviz_enabled = False
29- rviz_config = 'urdf.rviz'
3029
31- # ...............................................................
30+ # Create the launch configuration variables
31+ use_sim_time = LaunchConfiguration ('use_sim_time' )
32+ camera_enabled = LaunchConfiguration ('camera_enabled' )
33+ two_d_lidar_enabled = LaunchConfiguration ('two_d_lidar_enabled' )
34+ rviz_enabled = LaunchConfiguration ('rviz_enabled' )
35+ rviz_config = LaunchConfiguration ('rviz_config' )
3236
37+ # Declare the append environment variables
38+ append_env_var_gz_sim_resource_path = AppendEnvironmentVariable (
39+ name = 'GZ_SIM_RESOURCE_PATH' ,
40+ value = os .path .join (pkg_dir , "worlds" ) + ':' +
41+ os .path .join (pkg_dir , "models" , "warehouse_models" )
42+ )
3343
34- pkg_dir = get_package_share_directory ('atreus' )
35- gz_sim_pkg = get_package_share_directory ('ros_gz_sim' )
44+ # Declare the launch arguments
45+ declare_use_sim_time_arg = DeclareLaunchArgument (
46+ 'use_sim_time' , default_value = 'True' ,
47+ description = 'Flag to enable use_sim_time'
48+ )
49+ declare_world_name_arg = DeclareLaunchArgument (
50+ 'world_name' , default_value = world_path ,
51+ description = 'Choice of Gazebo World'
52+ )
53+ declare_camera_enabled_arg = DeclareLaunchArgument (
54+ 'camera_enabled' , default_value = 'False' ,
55+ description = 'Flag to enable camera'
56+ )
57+ declare_two_d_lidar_enabled_arg = DeclareLaunchArgument (
58+ 'two_d_lidar_enabled' , default_value = 'False' ,
59+ description = 'Flag to enable 2D LiDAR'
60+ )
61+ declare_rviz_enabled_arg = DeclareLaunchArgument (
62+ 'rviz_enabled' , default_value = 'False' ,
63+ description = 'Flag to enable RViz'
64+ )
65+ declare_rviz_config_arg = DeclareLaunchArgument (
66+ 'rviz_config' , default_value = rviz_config_path ,
67+ description = 'Full path to the RViz config file to use'
68+ )
3669
70+ # Include the Nodes
3771 gz_spawn_entity_node = Node (
3872 package = "ros_gz_sim" ,
3973 executable = "create" ,
@@ -45,49 +79,34 @@ def generate_launch_description():
4579 "-z" , "0.5" ,
4680 ]
4781 )
48-
49- gz_ros2_bridge = Node (
50- package = "ros_gz_bridge" ,
51- executable = "parameter_bridge" ,
52- arguments = [
53- "/cmd_vel@geometry_msgs/msg/Twist@gz.msgs.Twist" ,
54- "/clock@rosgraph_msgs/msg/Clock[gz.msgs.Clock" ,
55- "/odom@nav_msgs/msg/Odometry[gz.msgs.Odometry" ,
56- "/tf@tf2_msgs/msg/TFMessage[gz.msgs.Pose_V" ,
57- "/scan@sensor_msgs/msg/LaserScan[gz.msgs.LaserScan" ,
58- "/camera/camera_info@sensor_msgs/msg/CameraInfo[gz.msgs.CameraInfo" ,
59- "/camera/points@sensor_msgs/msg/PointCloud2[gz.msgs.PointCloudPacked" ,
60- "/imu@sensor_msgs/msg/Imu[gz.msgs.IMU" ,
61- "/world/default/model/atreus/joint_state@sensor_msgs/msg/JointState[gz.msgs.Model"
62- ],
63- remappings = [
64- ('/cmd_vel' , '/cmd_vel' ),
65- ('/odom' , '/odom' ),
66- ('/tf' , '/tf' ),
67- ('/scan' , '/scan' ),
68- ('/camera/camera_info' , '/camera/camera_info' ),
69- ('/camera/points' , '/camera/points' ),
70- ('/imu' , '/imu' ),
71- ('/world/default/model/atreus/joint_state' , '/joint_states' )
72- ]
82+ gz_ros2_bridge_node = Node (
83+ package = 'ros_gz_bridge' ,
84+ executable = 'parameter_bridge' ,
85+ name = 'bridge_ros_gz' ,
86+ parameters = [{
87+ 'config_file' : bridge_params_path ,
88+ 'use_sim_time' : use_sim_time
89+ }],
90+ output = 'screen' ,
7391 )
7492
75-
7693 robot_state_publisher_node = Node (
7794 package = 'robot_state_publisher' ,
7895 executable = 'robot_state_publisher' ,
79- parameters = [{'robot_description' : Command ( \
80- ['xacro ' , os .path .join (pkg_dir , 'urdf/ atreus.xacro' ),
81- ' camera_enabled:=' , LaunchConfiguration ( ' camera_enabled' ) ,
82- ' two_d_lidar_enabled:=' , LaunchConfiguration ( ' two_d_lidar_enabled' ),
96+ parameters = [{'robot_description' : Command (
97+ ['xacro ' , os .path .join (pkg_dir , 'urdf' , ' atreus.xacro' ),
98+ ' camera_enabled:=' , camera_enabled ,
99+ ' two_d_lidar_enabled:=' , two_d_lidar_enabled
83100 ])}]
84101 )
85102
86103 gz_sim_launch = IncludeLaunchDescription (
87- PythonLaunchDescriptionSource (os .path .join (gz_sim_pkg , "launch" , "gz_sim.launch.py" )),
104+ PythonLaunchDescriptionSource (
105+ PathJoinSubstitution (
106+ [FindPackageShare ('ros_gz_sim' ), 'launch' , 'gz_sim.launch.py' ])),
88107 launch_arguments = {
89108 "gz_args" : PythonExpression (
90- ["'" , os . path . join ( pkg_dir , 'worlds' , world_name ) , " -r'" ])
109+ ["'" , world_path , " -r'" ])
91110 }.items ()
92111 )
93112
@@ -96,54 +115,29 @@ def generate_launch_description():
96115 os .path .join (pkg_dir , "launch" , "description" , "rviz.launch.py" )),
97116 launch_arguments = {
98117 'gazebo_enabled' : 'True' ,
99- 'rviz_config' : LaunchConfiguration ('rviz_config' )
118+ 'camera_enabled' : camera_enabled ,
119+ 'two_d_lidar_enabled' : two_d_lidar_enabled ,
120+ 'rviz_config' : rviz_config ,
100121 }.items (),
101- condition = IfCondition (LaunchConfiguration ( ' rviz_enabled' ) )
122+ condition = IfCondition (rviz_enabled )
102123 )
103124
104- return LaunchDescription ([
105-
106- AppendEnvironmentVariable (
107- name = 'GZ_SIM_RESOURCE_PATH' ,
108- value = os .path .join (pkg_dir , "worlds" )),
109-
110- AppendEnvironmentVariable (
111- name = 'GZ_SIM_RESOURCE_PATH' ,
112- value = os .path .join (pkg_dir , "models" , "warehouse_models" )),
113-
114- DeclareLaunchArgument ('gui' , \
115- default_value = str (gui ), \
116- description = 'Flag to enable joint_state_publisher_gui' ),
117-
118- DeclareLaunchArgument ("use_sim_time" , \
119- default_value = str (use_sim_time ), \
120- description = "Use simulation/Gazebo clock" ),
121-
122- DeclareLaunchArgument ("world_name" , \
123- default_value = world_name , \
124- description = "Choice of Gazebo World" ),
125-
126- DeclareLaunchArgument ("camera_enabled" , \
127- default_value = str (camera_enabled ), \
128- description = "Camera Xacro Argument" ),
129-
130- DeclareLaunchArgument ("two_d_lidar_enabled" , \
131- default_value = str (two_d_lidar_enabled ), \
132- description = "2D LiDAR Xacro Argument" ),
125+ ld = LaunchDescription ()
133126
134- DeclareLaunchArgument ("rviz_enabled" , \
135- default_value = str (rviz_enabled ), \
136- description = "Start RViz" ),
127+ ld .add_action (append_env_var_gz_sim_resource_path )
137128
138- DeclareLaunchArgument ("rviz_config" , \
139- default_value = rviz_config , \
140- description = "RViz Config" ),
129+ ld .add_action (declare_use_sim_time_arg )
130+ ld .add_action (declare_world_name_arg )
131+ ld .add_action (declare_camera_enabled_arg )
132+ ld .add_action (declare_two_d_lidar_enabled_arg )
133+ ld .add_action (declare_rviz_enabled_arg )
134+ ld .add_action (declare_rviz_config_arg )
141135
142- robot_state_publisher_node ,
143- gz_ros2_bridge ,
144- gz_spawn_entity_node ,
136+ ld . add_action ( robot_state_publisher_node )
137+ ld . add_action ( gz_ros2_bridge_node )
138+ ld . add_action ( gz_spawn_entity_node )
145139
146- gz_sim_launch ,
147- rviz_launch ,
140+ ld . add_action ( gz_sim_launch )
141+ ld . add_action ( rviz_launch )
148142
149- ])
143+ return ld
0 commit comments