3 from launch
import LaunchDescription
4 from launch.substitutions
import TextSubstitution
5 from launch.substitutions
import LaunchConfiguration
6 from launch_ros.actions
import Node
7 from launch.actions
import DeclareLaunchArgument
8 from ament_index_python
import get_package_share_directory
9 from launch.conditions
import IfCondition
14 mvsimDir = get_package_share_directory(
"mvsim")
18 world_file_launch_arg = DeclareLaunchArgument(
19 "world_file", default_value=TextSubstitution(
20 text=os.path.join(mvsimDir,
'mvsim_tutorial',
'demo_road_circuit1.world.xml')))
22 headless_launch_arg = DeclareLaunchArgument(
23 "headless", default_value=
'False')
25 do_fake_localization_arg = DeclareLaunchArgument(
26 "do_fake_localization", default_value=
'True', description=
'publish tf odom -> base_link')
30 executable=
'mvsim_node',
34 os.path.join(mvsimDir,
'mvsim_tutorial',
35 'mvsim_ros2_params.yaml'),
37 "world_file": LaunchConfiguration(
'world_file'),
38 "headless": LaunchConfiguration(
'headless'),
39 "do_fake_localization": LaunchConfiguration(
'do_fake_localization'),
44 use_rviz = LaunchConfiguration(
'use_rviz')
46 declare_use_rviz_cmd = DeclareLaunchArgument(
49 description=
'Whether to start RVIZ')
53 condition=IfCondition(use_rviz),
59 '-d', [os.path.join(mvsimDir,
'mvsim_tutorial',
'demo_road_circuit1_ros2.rviz')]],
62 (
"/map", f
"/r{idx}/map"),
63 (
"/tf", f
"/r{idx}/tf"),
64 (
"/tf_static", f
"/r{idx}/tf_static"),
65 (
"/goal_pose", f
"/r{idx}/goal_pose"),
66 (
"/clicked_point", f
"/r{idx}/clicked_point"),
67 (
"/vehs/cmd_vel", f
"/r{idx}/cmd_vel"),
68 (
"/vehs/lidar1_points", f
"/r{idx}/lidar1_points"),
69 (
"/vehs/camera1/image_raw", f
"/r{idx}/camera1/image_raw"),
70 (
"/vehs/chassis_markers", f
"/r{idx}/chassis_markers"),
71 (
"/vehs/scanner1", f
"/r{idx}/scanner1"),
74 for idx
in range(1, 2)
82 '-d', [os.path.join(mvsimDir,
'mvsim_tutorial',
'demo_warehouse_ros2.rviz')]]
85 return LaunchDescription([
86 world_file_launch_arg,
89 do_fake_localization_arg,