|
3 | 3 |
|
4 | 4 | import os
|
5 | 5 | from ament_index_python.packages import get_package_share_directory
|
6 |
| -from launch import LaunchDescription |
7 |
| -from launch.actions import DeclareLaunchArgument |
8 |
| -from launch.actions import IncludeLaunchDescription, GroupAction |
| 6 | +from launch import LaunchDescription, LaunchContext |
| 7 | +from launch.actions import DeclareLaunchArgument, IncludeLaunchDescription, OpaqueFunction |
9 | 8 | from launch.launch_description_sources import PythonLaunchDescriptionSource
|
10 | 9 | from launch.substitutions import LaunchConfiguration, PythonExpression
|
11 |
| -from launch_ros.actions import Node, PushRosNamespace |
12 | 10 | from launch.conditions import IfCondition
|
13 | 11 |
|
| 12 | +""" |
| 13 | +Description: |
14 | 14 |
|
15 |
| -MY_NEO_ROBOT = os.environ['MY_ROBOT'] |
16 |
| -MY_NEO_ENVIRONMENT = os.environ['MAP_NAME'] |
| 15 | +You can launch this file using the following terminal commands: |
| 16 | +
|
| 17 | +This launch file is used to start the navigation for simulated Neobotix robot. |
| 18 | +It is launched after launching the "simulation.launch.py" file. |
| 19 | +
|
| 20 | +You can launch this file using the following terminal commands: |
| 21 | +
|
| 22 | +1. `ros2 launch neo_simulation2 navigation.launch.py --show-args` |
| 23 | + This command shows the arguments that can be passed to the launch file. |
| 24 | +2. `ros2 launch neo_simulation2 navigation.launch.py my_robot:=mp_500 map_name:=neo_track1 use_sim_time:=True use_multi_robots:=False use_amcl:=False` |
| 25 | + This command launches the simulation with sample values for the arguments. |
| 26 | + !(case is important for True/False) |
| 27 | +
|
| 28 | +""" |
| 29 | + |
| 30 | +# OpaqueFunction is used to perform setup actions during launch through a Python function |
| 31 | +def launch_setup(context: LaunchContext, my_neo_robot_arg, my_neo_env_arg, use_sim_time_arg, use_amcl_arg, use_multi_robots_arg, namespace_arg): |
| 32 | + my_neo_robot = my_neo_robot_arg.perform(context) |
| 33 | + my_neo_environment = my_neo_env_arg.perform(context) |
| 34 | + use_sim_time = use_sim_time_arg.perform(context) |
| 35 | + use_amcl = use_amcl_arg.perform(context) |
| 36 | + use_multi_robots = use_multi_robots_arg.perform(context) |
| 37 | + namespace = namespace_arg.perform(context) |
| 38 | + |
| 39 | + launch_actions = [] |
17 | 40 |
|
18 |
| -def generate_launch_description(): |
19 |
| - use_multi_robots = LaunchConfiguration('use_multi_robots', default='False') |
20 |
| - use_amcl = LaunchConfiguration('use_amcl', default='False') |
21 |
| - use_sim_time = LaunchConfiguration('use_sim_time', default='True') |
22 |
| - namespace = LaunchConfiguration('namespace', default='') |
23 |
| - use_namespace = LaunchConfiguration('use_namespace', default='False') |
24 | 41 | map_dir = LaunchConfiguration(
|
25 | 42 | 'map',
|
26 | 43 | default=os.path.join(
|
27 | 44 | get_package_share_directory('neo_simulation2'),
|
28 | 45 | 'maps',
|
29 |
| - MY_NEO_ENVIRONMENT+'.yaml')) |
| 46 | + my_neo_environment+'.yaml')) |
30 | 47 |
|
31 | 48 | param_file_name = 'navigation.yaml'
|
32 | 49 | param_dir = LaunchConfiguration(
|
33 | 50 | 'params_file',
|
34 | 51 | default=os.path.join(
|
35 | 52 | get_package_share_directory('neo_simulation2'),
|
36 |
| - 'configs/'+MY_NEO_ROBOT, |
| 53 | + 'configs/'+my_neo_robot, |
37 | 54 | param_file_name))
|
38 | 55 |
|
39 | 56 | nav2_launch_file_dir = os.path.join(get_package_share_directory('neo_nav2_bringup'), 'launch')
|
40 | 57 |
|
41 |
| - return LaunchDescription([ |
42 |
| - IncludeLaunchDescription( |
43 |
| - PythonLaunchDescriptionSource([nav2_launch_file_dir, '/localization_neo.launch.py']), |
44 |
| - condition=IfCondition(PythonExpression(['not ', use_amcl])), |
45 |
| - launch_arguments={ |
46 |
| - 'map': map_dir, |
47 |
| - 'use_sim_time': use_sim_time, |
48 |
| - 'use_multi_robots': use_multi_robots, |
49 |
| - 'params_file': param_dir, |
50 |
| - 'namespace': namespace}.items(), |
51 |
| - ), |
52 |
| - IncludeLaunchDescription( |
53 |
| - PythonLaunchDescriptionSource([nav2_launch_file_dir, '/localization_amcl.launch.py']), |
54 |
| - condition=IfCondition(use_amcl), |
55 |
| - launch_arguments={ |
56 |
| - 'map': map_dir, |
57 |
| - 'use_sim_time': use_sim_time, |
58 |
| - 'use_multi_robots': use_multi_robots, |
59 |
| - 'params_file': param_dir, |
60 |
| - 'namespace': namespace}.items(), |
61 |
| - ), |
62 |
| - |
63 |
| - IncludeLaunchDescription( |
64 |
| - PythonLaunchDescriptionSource([nav2_launch_file_dir, '/navigation_neo.launch.py']), |
65 |
| - launch_arguments={'namespace': namespace, |
66 |
| - 'use_sim_time': use_sim_time, |
67 |
| - 'params_file': param_dir}.items()), |
68 |
| - ]) |
| 58 | + # Define the IncludeLaunchDescription objects |
| 59 | + localization_neo_launch_description = IncludeLaunchDescription( |
| 60 | + PythonLaunchDescriptionSource([nav2_launch_file_dir, '/localization_neo.launch.py']), |
| 61 | + condition=IfCondition(PythonExpression(['not ', use_amcl])), |
| 62 | + launch_arguments={ |
| 63 | + 'map': map_dir, |
| 64 | + 'use_sim_time': use_sim_time, |
| 65 | + 'use_multi_robots': use_multi_robots, |
| 66 | + 'params_file': param_dir, |
| 67 | + 'namespace': namespace}.items(), |
| 68 | + ) |
| 69 | + |
| 70 | + localization_amcl_launch_description = IncludeLaunchDescription( |
| 71 | + PythonLaunchDescriptionSource([nav2_launch_file_dir, '/localization_amcl.launch.py']), |
| 72 | + condition=IfCondition(use_amcl), |
| 73 | + launch_arguments={ |
| 74 | + 'map': map_dir, |
| 75 | + 'use_sim_time': use_sim_time, |
| 76 | + 'use_multi_robots': use_multi_robots, |
| 77 | + 'params_file': param_dir, |
| 78 | + 'namespace': namespace}.items(), |
| 79 | + ) |
| 80 | + |
| 81 | + navigation_neo_launch_description = IncludeLaunchDescription( |
| 82 | + PythonLaunchDescriptionSource([nav2_launch_file_dir, '/navigation_neo.launch.py']), |
| 83 | + launch_arguments={ |
| 84 | + 'namespace': namespace, |
| 85 | + 'use_sim_time': use_sim_time, |
| 86 | + 'params_file': param_dir}.items(), |
| 87 | + ) |
| 88 | + |
| 89 | + # Append the IncludeLaunchDescription objects to the launch_actions list |
| 90 | + launch_actions.append(localization_neo_launch_description) |
| 91 | + launch_actions.append(localization_amcl_launch_description) |
| 92 | + launch_actions.append(navigation_neo_launch_description) |
| 93 | + |
| 94 | + return launch_actions |
| 95 | + |
| 96 | +def generate_launch_description(): |
| 97 | + ld = LaunchDescription() |
| 98 | + |
| 99 | + # Declare launch arguments 'my_robot' and 'map_name' with default values and descriptions |
| 100 | + declare_my_robot_arg = DeclareLaunchArgument( |
| 101 | + 'my_robot', default_value='mpo_700', |
| 102 | + description='Robot Types: "mpo_700", "mpo_500", "mp_400", "mp_500"' |
| 103 | + ) |
| 104 | + |
| 105 | + declare_map_name_arg = DeclareLaunchArgument( |
| 106 | + 'map_name', default_value='neo_workshop', |
| 107 | + description='Map Types: "neo_track1", "neo_workshop"' |
| 108 | + ) |
| 109 | + |
| 110 | + declare_use_multi_robots_cmd = DeclareLaunchArgument( |
| 111 | + 'use_multi_robots', default_value='False', |
| 112 | + description='Use multi robots "True/False"' |
| 113 | + ) |
| 114 | + |
| 115 | + declare_use_amcl_cmd = DeclareLaunchArgument( |
| 116 | + 'use_amcl', default_value='False', |
| 117 | + description='Use amcl for localization "True/False"' |
| 118 | + ) |
| 119 | + |
| 120 | + declare_use_sim_time_cmd = DeclareLaunchArgument( |
| 121 | + 'use_sim_time', default_value='True', |
| 122 | + description='Use simulation clock if true "True/False"' |
| 123 | + ) |
| 124 | + |
| 125 | + declare_namespace_cmd = DeclareLaunchArgument( |
| 126 | + 'robot_namespace', default_value='', |
| 127 | + description='Top-level namespace' |
| 128 | + ) |
| 129 | + |
| 130 | + # Create launch configuration variables for the launch arguments |
| 131 | + my_neo_robot_arg = LaunchConfiguration('my_robot') |
| 132 | + my_neo_env_arg = LaunchConfiguration('map_name') |
| 133 | + use_multi_robots = LaunchConfiguration('use_multi_robots') |
| 134 | + use_amcl = LaunchConfiguration('use_amcl') |
| 135 | + use_sim_time = LaunchConfiguration('use_sim_time') |
| 136 | + namespace = LaunchConfiguration('robot_namespace') |
| 137 | + |
| 138 | + ld.add_action(declare_my_robot_arg) |
| 139 | + ld.add_action(declare_map_name_arg) |
| 140 | + ld.add_action(declare_use_multi_robots_cmd) |
| 141 | + ld.add_action(declare_use_amcl_cmd) |
| 142 | + ld.add_action(declare_use_sim_time_cmd) |
| 143 | + ld.add_action(declare_namespace_cmd) |
| 144 | + |
| 145 | + context_arguments = [my_neo_robot_arg, my_neo_env_arg, use_sim_time, use_amcl, use_multi_robots, namespace] |
| 146 | + opq_func = OpaqueFunction(function = launch_setup, |
| 147 | + args = context_arguments) |
| 148 | + |
| 149 | + ld.add_action(opq_func) |
| 150 | + |
| 151 | + return ld |
0 commit comments