|
| 1 | +""" |
| 2 | +car_junction.launch.py |
| 3 | +
|
| 4 | +Entry point for the Car Junction exercise. |
| 5 | +""" |
| 6 | + |
1 | 7 | import os |
| 8 | + |
| 9 | +from ament_index_python.packages import get_package_share_directory |
| 10 | + |
2 | 11 | from launch import LaunchDescription |
3 | | -from launch.actions import DeclareLaunchArgument, IncludeLaunchDescription |
4 | | -from launch.conditions import IfCondition, UnlessCondition |
| 12 | +from launch.actions import ( |
| 13 | + DeclareLaunchArgument, |
| 14 | + IncludeLaunchDescription, |
| 15 | + SetEnvironmentVariable, |
| 16 | + AppendEnvironmentVariable, |
| 17 | +) |
5 | 18 | from launch.launch_description_sources import PythonLaunchDescriptionSource |
6 | | -from launch.substitutions import Command, LaunchConfiguration, PythonExpression |
| 19 | +from launch.substitutions import LaunchConfiguration, Command |
| 20 | +from launch_ros.actions import Node |
| 21 | +from launch.substitutions import LaunchConfiguration |
7 | 22 | from launch_ros.actions import Node |
8 | | -from launch_ros.substitutions import FindPackageShare |
9 | 23 |
|
10 | 24 |
|
11 | 25 | def generate_launch_description(): |
12 | 26 |
|
13 | | - # Set the path to the Gazebo ROS package |
14 | | - pkg_gazebo_ros = FindPackageShare(package="gazebo_ros").find("gazebo_ros") |
15 | | - |
16 | | - # Set the path to this package. |
17 | | - pkg_share = FindPackageShare(package="custom_robots").find("custom_robots") |
18 | | - |
19 | | - # Set the path to the world file |
| 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") |
20 | 30 | world_file_name = "road_junction.world" |
21 | | - world_path = os.path.join(pkg_share, "worlds", world_file_name) |
| 31 | + worlds_dir = "/opt/jderobot/Worlds" |
| 32 | + world_path = os.path.join(worlds_dir, world_file_name) |
22 | 33 |
|
23 | | - # Set the path to the SDF model files. |
24 | | - gazebo_models_path = os.path.join(pkg_share, "models") |
25 | | - os.environ["GAZEBO_MODEL_PATH"] = ( |
26 | | - f"{os.environ.get('GAZEBO_MODEL_PATH', '')}:{':'.join(gazebo_models_path)}" |
27 | | - ) |
28 | | - |
29 | | - start_ros_gazebo_bridge = ( |
30 | | - Node( |
31 | | - package="ros_gz_bridge", |
32 | | - executable="parameter_bridge", |
33 | | - arguments=[ |
34 | | - "/clock@rosgraph_msgs/msg/Clock[gz.msgs.Clock", |
35 | | - "/cmd_vel@geometry_msgs/msg/Twist]gz.msgs.Twist", |
36 | | - "/odom@nav_msgs/msg/Odometry]gz.msgs.Odometry", |
37 | | - "/waymo/lidar/points@sensor_msgs/msg/PointCloud2[gz.msgs.PointCloudPacked", |
38 | | - "/waymo/camera_info@sensor_msgs/msg/CameraInfo[gz.msgs.CameraInfo", |
39 | | - ], |
40 | | - parameters=[{"use_sim_time": True}], |
41 | | - output="screen", |
| 34 | + gazebo_server = IncludeLaunchDescription( |
| 35 | + PythonLaunchDescriptionSource( |
| 36 | + os.path.join(ros_gz_sim, "launch", "gz_sim.launch.py") |
42 | 37 | ), |
43 | | - ) |
44 | | - |
45 | | - start_ros_gazebo_image_bridge = Node( |
46 | | - package="ros_gz_image", |
47 | | - executable="image_bridge", |
48 | | - arguments=["/waymo/camera_front@sensor_msgs/msg/Image[gz.msgs.Image"], |
49 | | - output="screen", |
50 | | - ) |
51 | | - |
52 | | - ########### YOU DO NOT NEED TO CHANGE ANYTHING BELOW THIS LINE ############## |
53 | | - # Launch configuration variables specific to simulation |
54 | | - headless = LaunchConfiguration("headless") |
55 | | - use_sim_time = LaunchConfiguration("use_sim_time") |
56 | | - use_simulator = LaunchConfiguration("use_simulator") |
57 | | - world = LaunchConfiguration("world") |
58 | | - |
59 | | - declare_simulator_cmd = DeclareLaunchArgument( |
60 | | - name="headless", |
61 | | - default_value="False", |
62 | | - description="Whether to execute gzclient", |
63 | | - ) |
64 | | - |
65 | | - declare_use_sim_time_cmd = DeclareLaunchArgument( |
66 | | - name="use_sim_time", |
67 | | - default_value="true", |
68 | | - description="Use simulation (Gazebo) clock if true", |
| 38 | + launch_arguments={ |
| 39 | + "gz_args": ["-r -s -v4 ", world_path], |
| 40 | + "on_exit_shutdown": "true", |
| 41 | + }.items(), |
69 | 42 | ) |
70 | 43 |
|
71 | 44 | declare_use_simulator_cmd = DeclareLaunchArgument( |
72 | 45 | name="use_simulator", |
73 | 46 | default_value="True", |
74 | 47 | description="Whether to start the simulator", |
75 | 48 | ) |
76 | | - |
77 | | - declare_world_cmd = DeclareLaunchArgument( |
78 | | - name="world", |
79 | | - default_value=world_path, |
80 | | - description="Full path to the world model file to load", |
| 49 | + world_entity_cmd = Node( |
| 50 | + package="ros_gz_sim", |
| 51 | + executable="create", |
| 52 | + arguments=["-name", "world", "-file", world_path], |
| 53 | + output="screen", |
81 | 54 | ) |
82 | 55 |
|
83 | | - # Specify the actions |
84 | | - |
85 | | - # Start Gazebo server |
86 | | - start_gazebo_server_cmd = IncludeLaunchDescription( |
87 | | - PythonLaunchDescriptionSource( |
88 | | - os.path.join(pkg_gazebo_ros, "launch", "gzserver.launch.py") |
89 | | - ), |
90 | | - condition=IfCondition(use_simulator), |
91 | | - launch_arguments={"world": world}.items(), |
| 56 | + start_ros_gazebo_bridge = Node( |
| 57 | + package="ros_gz_bridge", |
| 58 | + executable="parameter_bridge", |
| 59 | + arguments=[ |
| 60 | + "/clock@rosgraph_msgs/msg/Clock[gz.msgs.Clock", |
| 61 | + "/cmd_vel@geometry_msgs/msg/Twist]gz.msgs.Twist", |
| 62 | + "/odom@nav_msgs/msg/Odometry]gz.msgs.Odometry", |
| 63 | + "/waymo/lidar/points@sensor_msgs/msg/PointCloud2[gz.msgs.PointCloudPacked", |
| 64 | + "/waymo/camera_info@sensor_msgs/msg/CameraInfo[gz.msgs.CameraInfo", |
| 65 | + ], |
| 66 | + parameters=[{'use_sim_time': True}], |
| 67 | + output="screen", |
| 68 | + ) |
| 69 | + |
| 70 | + # Set the path to the SDF model files. |
| 71 | + gazebo_models_path = os.path.join(pkg_share, "models") |
| 72 | + os.environ["GAZEBO_MODEL_PATH"] = ( |
| 73 | + f"{os.environ.get('GAZEBO_MODEL_PATH', '')}:{':'.join(gazebo_models_path)}" |
92 | 74 | ) |
93 | 75 |
|
94 | | - # Start Gazebo client |
95 | | - start_gazebo_client_cmd = IncludeLaunchDescription( |
96 | | - PythonLaunchDescriptionSource( |
97 | | - os.path.join(pkg_gazebo_ros, "launch", "gzclient.launch.py") |
98 | | - ), |
99 | | - condition=IfCondition(PythonExpression([use_simulator, " and not ", headless])), |
| 76 | + start_ros_gazebo_image_bridge = Node( |
| 77 | + package="ros_gz_image", |
| 78 | + executable="image_bridge", |
| 79 | + arguments=["/waymo/camera_front@sensor_msgs/msg/Image[gz.msgs.Image"], |
| 80 | + output="screen", |
100 | 81 | ) |
101 | 82 |
|
102 | 83 | # Create the launch description and populate |
103 | 84 | ld = LaunchDescription() |
104 | | - |
105 | | - # Declare the launch options |
106 | | - ld.add_action(declare_simulator_cmd) |
107 | | - ld.add_action(declare_use_sim_time_cmd) |
108 | | - ld.add_action(declare_use_simulator_cmd) |
109 | | - ld.add_action(declare_world_cmd) |
110 | | - |
111 | | - # Add any actions |
112 | | - ld.add_action(start_gazebo_server_cmd) |
113 | | - ld.add_action(start_gazebo_client_cmd) |
| 85 | + ld.add_action(gazebo_server) |
| 86 | + ld.add_action(world_entity_cmd) |
114 | 87 | ld.add_action(start_ros_gazebo_bridge) |
115 | 88 | ld.add_action(start_ros_gazebo_image_bridge) |
116 | 89 |
|
|
0 commit comments