launch_world.launch.py
Go to the documentation of this file.
1 # Generic ROS2 launch file
2 # Read: https://mvsimulator.readthedocs.io/en/latest/mvsim_node.html
3 
4 from launch import LaunchDescription
5 from launch.substitutions import LaunchConfiguration
6 from launch_ros.actions import Node
7 from launch.actions import DeclareLaunchArgument
8 from launch.conditions import IfCondition
9 import os
10 
11 
13 
14  # args that can be set from the command line or a default will be used
15  world_file_launch_arg = DeclareLaunchArgument(
16  "world_file", description='Path to the *.world.xml file to load')
17 
18  headless_launch_arg = DeclareLaunchArgument(
19  "headless", default_value='False')
20 
21  do_fake_localization_arg = DeclareLaunchArgument(
22  "do_fake_localization", default_value='True', description='publish fake identity tf "map" -> "odom"')
23 
24  publish_tf_odom2baselink_arg = DeclareLaunchArgument(
25  "publish_tf_odom2baselink", default_value='True', description='publish tf "odom" -> "base_link"')
26 
27  force_publish_vehicle_namespace_arg = DeclareLaunchArgument(
28  "force_publish_vehicle_namespace", default_value='False',
29  description='Use vehicle name namespace even if there is only one vehicle')
30 
31  use_rviz_arg = DeclareLaunchArgument(
32  'use_rviz', default_value='True',
33  description='Whether to launch RViz2'
34  )
35 
36  rviz_config_file_arg = DeclareLaunchArgument(
37  'rviz_config_file', default_value='',
38  description='If use_rviz:="True", the configuration file for rviz'
39  )
40 
41  mvsim_node = Node(
42  package='mvsim',
43  executable='mvsim_node',
44  name='mvsim',
45  output='screen',
46  parameters=[
47  {
48  "world_file": LaunchConfiguration('world_file'),
49  "headless": LaunchConfiguration('headless'),
50  "do_fake_localization": LaunchConfiguration('do_fake_localization'),
51  "publish_tf_odom2baselink": LaunchConfiguration('publish_tf_odom2baselink'),
52  "force_publish_vehicle_namespace": LaunchConfiguration('force_publish_vehicle_namespace'),
53  }]
54  )
55 
56  rviz2_node = Node(
57  condition=IfCondition(LaunchConfiguration('use_rviz')),
58  package='rviz2',
59  executable='rviz2',
60  name='rviz2',
61  arguments=[] if LaunchConfiguration('rviz_config_file') == '' else [
62  '-d', LaunchConfiguration('rviz_config_file')]
63  )
64 
65  return LaunchDescription([
66  world_file_launch_arg,
67  headless_launch_arg,
68  do_fake_localization_arg,
69  publish_tf_odom2baselink_arg,
70  force_publish_vehicle_namespace_arg,
71  use_rviz_arg,
72  rviz_config_file_arg,
73  mvsim_node,
74  rviz2_node
75  ])
launch_world.generate_launch_description
def generate_launch_description()
Definition: launch_world.launch.py:12


mvsim
Author(s):
autogenerated on Wed May 28 2025 02:13:08