|
1 | | -# Copyright (c) 2018 Intel Corporation |
2 | | -# |
3 | | -# Licensed under the Apache License, Version 2.0 (the "License"); |
4 | | -# you may not use this file except in compliance with the License. |
5 | | -# You may obtain a copy of the License at |
6 | | -# |
7 | | -# http://www.apache.org/licenses/LICENSE-2.0 |
8 | | -# |
9 | | -# Unless required by applicable law or agreed to in writing, software |
10 | | -# distributed under the License is distributed on an "AS IS" BASIS, |
11 | | -# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. |
12 | | -# See the License for the specific language governing permissions and |
13 | | -# limitations under the License. |
14 | | - |
15 | 1 | import os |
16 | 2 |
|
17 | 3 | from ament_index_python.packages import get_package_share_directory |
18 | | - |
19 | 4 | from launch import LaunchDescription |
20 | | -from launch.actions import ExecuteProcess, SetEnvironmentVariable |
| 5 | +from launch.actions import DeclareLaunchArgument, ExecuteProcess, IncludeLaunchDescription |
| 6 | +from launch.launch_description_sources import PythonLaunchDescriptionSource |
| 7 | +from launch.substitutions import Command, LaunchConfiguration |
21 | 8 | from launch_ros.actions import Node |
| 9 | +from ros_gz_bridge.actions import RosGzBridge |
| 10 | +from ros_gz_sim.actions import GzServer |
22 | 11 |
|
23 | 12 |
|
24 | 13 | def generate_launch_description(): |
25 | | - # Get the launch directory |
26 | | - gps_wpf_dir = get_package_share_directory( |
27 | | - "nav2_gps_waypoint_follower_demo") |
28 | | - launch_dir = os.path.join(gps_wpf_dir, 'launch') |
29 | | - world = os.path.join(gps_wpf_dir, "worlds", "sonoma_raceway.world") |
30 | | - |
31 | | - urdf = os.path.join(gps_wpf_dir, 'urdf', 'turtlebot3_waffle_gps.urdf') |
32 | | - with open(urdf, 'r') as infp: |
33 | | - robot_description = infp.read() |
34 | | - |
35 | | - models_dir = os.path.join(gps_wpf_dir, "models") |
36 | | - models_dir += os.pathsep + \ |
37 | | - f"/opt/ros/{os.getenv('ROS_DISTRO')}/share/turtlebot3_gazebo/models" |
38 | | - set_gazebo_model_path_cmd = None |
39 | | - |
40 | | - if 'GAZEBO_MODEL_PATH' in os.environ: |
41 | | - gazebo_model_path = os.environ['GAZEBO_MODEL_PATH'] + \ |
42 | | - os.pathsep + models_dir |
43 | | - set_gazebo_model_path_cmd = SetEnvironmentVariable( |
44 | | - "GAZEBO_MODEL_PATH", gazebo_model_path) |
45 | | - else: |
46 | | - set_gazebo_model_path_cmd = SetEnvironmentVariable( |
47 | | - "GAZEBO_MODEL_PATH", models_dir) |
48 | | - |
49 | | - set_tb3_model_cmd = SetEnvironmentVariable("TURTLEBOT3_MODEL", "waffle") |
50 | | - |
51 | | - # Specify the actions |
52 | | - start_gazebo_server_cmd = ExecuteProcess( |
53 | | - cmd=['gzserver', '-s', 'libgazebo_ros_init.so', |
54 | | - '-s', 'libgazebo_ros_factory.so', world], |
55 | | - cwd=[launch_dir], output='both') |
56 | | - |
57 | | - start_gazebo_client_cmd = ExecuteProcess( |
58 | | - cmd=['gzclient'], |
59 | | - cwd=[launch_dir], output='both') |
60 | | - |
61 | | - start_robot_state_publisher_cmd = Node( |
| 14 | + world_pkg_share = get_package_share_directory('nav2_gps_waypoint_follower_demo') |
| 15 | + robot_pkg_share = get_package_share_directory('sam_bot_description') |
| 16 | + ros_gz_sim_share = get_package_share_directory('ros_gz_sim') |
| 17 | + gz_spawn_model_launch_source = os.path.join(ros_gz_sim_share, "launch", "gz_spawn_model.launch.py") |
| 18 | + default_model_path = os.path.join(robot_pkg_share, 'src', 'description', 'sam_bot_description.sdf') |
| 19 | + world_path = os.path.join(world_pkg_share, 'worlds', 'sonoma_world.sdf') |
| 20 | + bridge_config_path = os.path.join(robot_pkg_share, 'config', 'bridge_config.yaml') |
| 21 | + |
| 22 | + robot_state_publisher_node = Node( |
62 | 23 | package='robot_state_publisher', |
63 | 24 | executable='robot_state_publisher', |
64 | | - name='robot_state_publisher', |
65 | | - output='both', |
66 | | - parameters=[{'robot_description': robot_description}]) |
67 | | - |
68 | | - # Create the launch description and populate |
69 | | - ld = LaunchDescription() |
70 | | - |
71 | | - # Set gazebo up to find models properly |
72 | | - ld.add_action(set_gazebo_model_path_cmd) |
73 | | - ld.add_action(set_tb3_model_cmd) |
74 | | - |
75 | | - # simulator launch |
76 | | - ld.add_action(start_gazebo_server_cmd) |
77 | | - ld.add_action(start_gazebo_client_cmd) |
78 | | - |
79 | | - # robot state publisher launch |
80 | | - ld.add_action(start_robot_state_publisher_cmd) |
81 | | - |
82 | | - return ld |
| 25 | + parameters=[{'robot_description': Command(['xacro ', LaunchConfiguration('model')])}, {'use_sim_time': LaunchConfiguration('use_sim_time')}] |
| 26 | + ) |
| 27 | + |
| 28 | + gz_server = GzServer( |
| 29 | + world_sdf_file=world_path, |
| 30 | + container_name='ros_gz_container', |
| 31 | + create_own_container='True', |
| 32 | + use_composition='True', |
| 33 | + ) |
| 34 | + ros_gz_bridge = RosGzBridge( |
| 35 | + bridge_name='ros_gz_bridge', |
| 36 | + config_file=bridge_config_path, |
| 37 | + container_name='ros_gz_container', |
| 38 | + |
| 39 | + create_own_container='False', |
| 40 | + use_composition='True', |
| 41 | + ) |
| 42 | + camera_bridge_image = Node( |
| 43 | + package='ros_gz_image', |
| 44 | + executable='image_bridge', |
| 45 | + name='bridge_gz_ros_camera_image', |
| 46 | + output='screen', |
| 47 | + parameters=[{'use_sim_time': True}], |
| 48 | + arguments=['/depth_camera/image'], |
| 49 | + ) |
| 50 | + camera_bridge_depth = Node( |
| 51 | + package='ros_gz_image', |
| 52 | + executable='image_bridge', |
| 53 | + name='bridge_gz_ros_camera_depth', |
| 54 | + output='screen', |
| 55 | + parameters=[{'use_sim_time': True}], |
| 56 | + arguments=['/depth_camera/depth_image'], |
| 57 | + ) |
| 58 | + spawn_entity = IncludeLaunchDescription( |
| 59 | + PythonLaunchDescriptionSource(gz_spawn_model_launch_source), |
| 60 | + launch_arguments={ |
| 61 | + 'world': 'my_world', |
| 62 | + 'topic': '/robot_description', |
| 63 | + 'entity_name': 'sam_bot', |
| 64 | + 'x': '2.0', # meters |
| 65 | + 'y': '-2.5', |
| 66 | + 'z': '0.65', |
| 67 | + 'R': '0.0', # roll (radians) |
| 68 | + 'P': '0.0', # pitch |
| 69 | + 'Y': '0.0', # yaw |
| 70 | + }.items(), |
| 71 | + ) |
| 72 | + |
| 73 | + return LaunchDescription([ |
| 74 | + DeclareLaunchArgument(name='model', default_value=default_model_path, description='Absolute path to robot model file'), |
| 75 | + DeclareLaunchArgument(name='use_sim_time', default_value='True', description='Flag to enable use_sim_time'), |
| 76 | + ExecuteProcess(cmd=['gz', 'sim', '-g'], output='screen'), |
| 77 | + robot_state_publisher_node, |
| 78 | + gz_server, |
| 79 | + ros_gz_bridge, |
| 80 | + camera_bridge_image, |
| 81 | + camera_bridge_depth, |
| 82 | + spawn_entity, |
| 83 | + ]) |
0 commit comments