1+ """
2+ car_junction.launch.py
3+
4+ Entry point for the Car Junction exercise.
5+ """
6+
17import os
8+
9+ from ament_index_python .packages import get_package_share_directory
10+
211from launch import LaunchDescription
12+ from launch .actions import (
13+ DeclareLaunchArgument ,
14+ IncludeLaunchDescription ,
15+ SetEnvironmentVariable ,
16+ AppendEnvironmentVariable ,
17+ )
318from launch .actions import DeclareLaunchArgument , IncludeLaunchDescription
4- from launch .conditions import IfCondition , UnlessCondition
19+ from launch .conditions import IfCondition
520from launch .launch_description_sources import PythonLaunchDescriptionSource
6- from launch .substitutions import Command , LaunchConfiguration , PythonExpression
21+ from launch .substitutions import LaunchConfiguration , Command
722from launch_ros .actions import Node
8- from launch_ros .substitutions import FindPackageShare
923
1024
1125def generate_launch_description ():
1226
13- custom_robots_share = get_package_share_directory ("custom_robots" )
14- world_path = os .path .join (
15- custom_robots_share , "worlds" , "road_junction.world"
27+ package_dir = get_package_share_directory ("custom_robots" )
28+ ros_gz_sim = get_package_share_directory ("ros_gz_sim" )
29+ use_sim_time = LaunchConfiguration ("use_sim_time" , default = "true" )
30+ world_file_name = "road_junction.world"
31+ worlds_dir = "/opt/jderobot/Worlds"
32+ world_path = os .path .join (worlds_dir , world_file_name )
33+
34+ # Start Gazebo server
35+ gazebo_server = IncludeLaunchDescription (
36+ PythonLaunchDescriptionSource (
37+ os .path .join (ros_gz_sim , "launch" , "gz_sim.launch.py" )
38+ ),
39+ launch_arguments = {
40+ "gz_args" : ["-r -s -v4 " , world_path ],
41+ "on_exit_shutdown" : "true" ,
42+ }.items (),
43+ )
44+ world_entity_cmd = Node (
45+ package = "ros_gz_sim" ,
46+ executable = "create" ,
47+ arguments = ["-name" , "world" , "-file" , world_path ],
48+ output = "screen" ,
1649 )
17- # Set the path to the SDF model files.
18- gazebo_models_path = os .path .join (pkg_share , "models" )
19- os .environ [
20- "GAZEBO_MODEL_PATH"
21- ] = f"{ os .environ .get ('GAZEBO_MODEL_PATH' , '' )} :{ ':' .join (gazebo_models_path )} "
2250
2351 start_ros_gazebo_bridge = Node (
2452 package = "ros_gz_bridge" ,
@@ -31,78 +59,26 @@ def generate_launch_description():
3159 "/waymo/camera_info@sensor_msgs/msg/CameraInfo[gz.msgs.CameraInfo" ,
3260 ],
3361 parameters = [{'use_sim_time' : True }],
34- output = "screen"
35- ),
62+ output = "screen" ,
63+ )
3664
3765 start_ros_gazebo_image_bridge = Node (
3866 package = "ros_gz_image" ,
3967 executable = "image_bridge" ,
4068 arguments = ["/waymo/camera_front@sensor_msgs/msg/Image[gz.msgs.Image" ],
4169 output = "screen" ,
4270 )
43-
44- ########### YOU DO NOT NEED TO CHANGE ANYTHING BELOW THIS LINE ##############
45- # Launch configuration variables specific to simulation
46- headless = LaunchConfiguration ("headless" )
47- use_sim_time = LaunchConfiguration ("use_sim_time" )
48- use_simulator = LaunchConfiguration ("use_simulator" )
49- world = LaunchConfiguration ("world" )
50-
51- declare_simulator_cmd = DeclareLaunchArgument (
52- name = "headless" ,
53- default_value = "False" ,
54- description = "Whether to execute gzclient" ,
55- )
56-
57- declare_use_sim_time_cmd = DeclareLaunchArgument (
58- name = "use_sim_time" ,
59- default_value = "true" ,
60- description = "Use simulation (Gazebo) clock if true" ,
61- )
62-
63- declare_use_simulator_cmd = DeclareLaunchArgument (
64- name = "use_simulator" ,
65- default_value = "True" ,
66- description = "Whether to start the simulator" ,
67- )
68-
69- declare_world_cmd = DeclareLaunchArgument (
70- name = "world" ,
71- default_value = world_path ,
72- description = "Full path to the world model file to load" ,
73- )
74-
75- # Specify the actions
76-
77- # Start Gazebo server
78- start_gazebo_server_cmd = IncludeLaunchDescription (
79- PythonLaunchDescriptionSource (
80- os .path .join (pkg_gazebo_ros , "launch" , "gzserver.launch.py" )
81- ),
82- condition = IfCondition (use_simulator ),
83- launch_arguments = {"world" : world }.items (),
84- )
85-
86- # Start Gazebo client
87- start_gazebo_client_cmd = IncludeLaunchDescription (
88- PythonLaunchDescriptionSource (
89- os .path .join (pkg_gazebo_ros , "launch" , "gzclient.launch.py" )
90- ),
91- condition = IfCondition (PythonExpression ([use_simulator , " and not " , headless ])),
92- )
93-
9471 # Create the launch description and populate
9572 ld = LaunchDescription ()
9673
97- # Declare the launch options
98- ld .add_action (declare_simulator_cmd )
99- ld .add_action (declare_use_sim_time_cmd )
100- ld .add_action (declare_use_simulator_cmd )
101- ld .add_action (declare_world_cmd )
102-
10374 # Add any actions
104- ld .add_action (start_gazebo_server_cmd )
105- ld .add_action (start_gazebo_client_cmd )
75+ ld .add_action (SetEnvironmentVariable ("GZ_SIM_RESOURCE_PATH" , gazebo_models_path ))
76+ set_env_vars_resources = AppendEnvironmentVariable (
77+ "GZ_SIM_RESOURCE_PATH" , os .path .join (package_dir , "models" )
78+ )
79+ ld .add_action (set_env_vars_resources )
80+ ld .add_action (gazebo_server )
81+ ld .add_action (world_entity_cmd )
10682 ld .add_action (start_ros_gazebo_bridge )
10783 ld .add_action (start_ros_gazebo_image_bridge )
10884
0 commit comments