Skip to content

Commit 07d82c4

Browse files
AdarshKaranpadhupradheep
authored andcommitted
Refactor/launch args sim nav (#86)
* TASK1- made changes to simulation and navigation launch files * Refactored simulation and navigation launch files * Updated_Refactored launch arguments * Updated the comment changes * Changed indentation * Final changes
1 parent a576c21 commit 07d82c4

File tree

2 files changed

+218
-77
lines changed

2 files changed

+218
-77
lines changed

launch/navigation.launch.py

+125-42
Original file line numberDiff line numberDiff line change
@@ -3,66 +3,149 @@
33

44
import os
55
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
98
from launch.launch_description_sources import PythonLaunchDescriptionSource
109
from launch.substitutions import LaunchConfiguration, PythonExpression
11-
from launch_ros.actions import Node, PushRosNamespace
1210
from launch.conditions import IfCondition
1311

12+
"""
13+
Description:
1414
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 = []
1740

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')
2441
map_dir = LaunchConfiguration(
2542
'map',
2643
default=os.path.join(
2744
get_package_share_directory('neo_simulation2'),
2845
'maps',
29-
MY_NEO_ENVIRONMENT+'.yaml'))
46+
my_neo_environment+'.yaml'))
3047

3148
param_file_name = 'navigation.yaml'
3249
param_dir = LaunchConfiguration(
3350
'params_file',
3451
default=os.path.join(
3552
get_package_share_directory('neo_simulation2'),
36-
'configs/'+MY_NEO_ROBOT,
53+
'configs/'+my_neo_robot,
3754
param_file_name))
3855

3956
nav2_launch_file_dir = os.path.join(get_package_share_directory('neo_nav2_bringup'), 'launch')
4057

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

launch/simulation.launch.py

+93-35
Original file line numberDiff line numberDiff line change
@@ -3,49 +3,40 @@
33

44
import launch
55
from ament_index_python.packages import get_package_share_directory
6-
from launch import LaunchDescription
7-
from launch.actions import DeclareLaunchArgument, IncludeLaunchDescription, ExecuteProcess
6+
from launch import LaunchDescription, LaunchContext
7+
from launch.actions import DeclareLaunchArgument, IncludeLaunchDescription, OpaqueFunction
88
from launch.launch_description_sources import PythonLaunchDescriptionSource
9-
from launch.substitutions import ThisLaunchFileDir, LaunchConfiguration
9+
from launch.substitutions import LaunchConfiguration
1010
from launch_ros.actions import Node
1111
import os
12-
from pathlib import Path
1312

14-
MY_NEO_ROBOT = os.environ['MY_ROBOT']
15-
MY_NEO_ENVIRONMENT = os.environ['MAP_NAME']
13+
"""
14+
Description:
1615
17-
def generate_launch_description():
18-
default_world_path = os.path.join(get_package_share_directory('neo_simulation2'), 'worlds', MY_NEO_ENVIRONMENT + '.world')
19-
20-
use_sim_time = LaunchConfiguration('use_sim_time', default='true')
16+
This launch file is used to start a ROS2 simulation for a Neobotix robot in a specified environment.
17+
It sets up the Gazebo simulator with the chosen robot and environment,
18+
optionally starts the robot state publisher, and enables keyboard teleoperation.
2119
22-
robot_dir = LaunchConfiguration(
23-
'robot_dir',
24-
default=os.path.join(get_package_share_directory('neo_simulation2'),
25-
'robots/'+MY_NEO_ROBOT,
26-
MY_NEO_ROBOT+'.urdf'))
20+
You can launch this file using the following terminal commands:
2721
28-
declare_use_sim_time_cmd = DeclareLaunchArgument(
29-
'use_sim_time',
30-
default_value='false',
31-
description='Use simulation (Gazebo) clock if true')
32-
use_robot_state_pub = LaunchConfiguration('use_robot_state_pub')
33-
urdf = os.path.join(get_package_share_directory('neo_simulation2'), 'robots/'+MY_NEO_ROBOT+'/', MY_NEO_ROBOT+'.urdf')
22+
1. `ros2 launch neo_simulation2 simulation.launch.py --show-args`
23+
This command shows the arguments that can be passed to the launch file.
24+
2. `ros2 launch neo_simulation2 simulation.launch.py my_robot:=mp_500 map_name:=neo_track1 use_sim_time:=true use_robot_state_pub:=true`
25+
This command launches the simulation with sample values for the arguments.
26+
"""
3427

35-
spawn_entity = Node(package='gazebo_ros', executable='spawn_entity.py',arguments=['-entity', MY_NEO_ROBOT, '-file', urdf], output='screen')
28+
# OpaqueFunction is used to perform setup actions during launch through a Python function
29+
def launch_setup(context: LaunchContext, my_neo_robot_arg, my_neo_env_arg, use_sim_time_arg):
30+
# Create a list to hold all the nodes
31+
launch_actions = []
32+
# The perform method of a LaunchConfiguration is called to evaluate its value.
33+
my_neo_robot = my_neo_robot_arg.perform(context)
34+
my_neo_environment = my_neo_env_arg.perform(context)
35+
use_sim_time = use_sim_time_arg.perform(context).lower() == 'true'
3636

37-
start_robot_state_publisher_cmd = Node(
38-
package='robot_state_publisher',
39-
executable='robot_state_publisher',
40-
name='robot_state_publisher',
41-
output='screen',
42-
parameters=[{'use_sim_time': use_sim_time}],
43-
arguments=[urdf])
44-
45-
teleop = Node(package='teleop_twist_keyboard',executable="teleop_twist_keyboard",
46-
output='screen',
47-
prefix = 'xterm -e',
48-
name='teleop')
37+
# Get the required paths for the world and robot robot_description_urdf
38+
default_world_path = os.path.join(get_package_share_directory('neo_simulation2'), 'worlds', my_neo_environment + '.world')
39+
robot_description_urdf = os.path.join(get_package_share_directory('neo_simulation2'), 'robots/'+my_neo_robot+'/', my_neo_robot+'.urdf')
4940

5041
gazebo = IncludeLaunchDescription(
5142
PythonLaunchDescriptionSource(
@@ -57,4 +48,71 @@ def generate_launch_description():
5748
}.items()
5849
)
5950

60-
return LaunchDescription([spawn_entity, start_robot_state_publisher_cmd, teleop, gazebo])
51+
spawn_entity = Node(
52+
package='gazebo_ros',
53+
executable='spawn_entity.py',
54+
arguments=['-entity', my_neo_robot,'-file', robot_description_urdf],
55+
output='screen')
56+
57+
# Start the robot state publisher node
58+
start_robot_state_publisher_cmd = Node(
59+
package='robot_state_publisher',
60+
executable='robot_state_publisher',
61+
name='robot_state_publisher',
62+
output='screen',
63+
parameters=[{'use_sim_time': use_sim_time}],
64+
arguments=[robot_description_urdf])
65+
# Append the node to the launch_actions only if use_robot_state_pub is true
66+
launch_actions.append(start_robot_state_publisher_cmd)
67+
68+
teleop = Node(
69+
package='teleop_twist_keyboard',
70+
executable="teleop_twist_keyboard",
71+
output='screen',
72+
prefix = 'xterm -e',
73+
name='teleop')
74+
75+
# The required nodes can just be appended to the launch_actions list
76+
launch_actions.append(gazebo)
77+
launch_actions.append(spawn_entity)
78+
launch_actions.append(teleop)
79+
80+
return launch_actions
81+
82+
def generate_launch_description():
83+
ld = LaunchDescription()
84+
85+
# Declare launch arguments 'my_robot' and 'map_name' with default values and descriptions
86+
declare_my_robot_arg = DeclareLaunchArgument(
87+
'my_robot', default_value='mpo_700',
88+
description='Robot Types: "mpo_700", "mpo_500", "mp_400", "mp_500"'
89+
)
90+
91+
declare_map_name_arg = DeclareLaunchArgument(
92+
'map_name', default_value='neo_workshop',
93+
description='Map Types: "neo_track1", "neo_workshop"'
94+
)
95+
96+
declare_use_sim_time_arg = DeclareLaunchArgument(
97+
'use_sim_time', default_value='True',
98+
description='Use simulation clock if true (true/false)'
99+
)
100+
101+
# Create launch configuration variables for the robot and map name
102+
my_neo_robot_arg = LaunchConfiguration('my_robot')
103+
my_neo_env_arg = LaunchConfiguration('map_name')
104+
use_sim_time_arg = LaunchConfiguration('use_sim_time')
105+
106+
ld.add_action(declare_my_robot_arg)
107+
ld.add_action(declare_map_name_arg)
108+
ld.add_action(declare_use_sim_time_arg)
109+
110+
context_arguments = [my_neo_robot_arg, my_neo_env_arg, use_sim_time_arg]
111+
opq_function = OpaqueFunction(
112+
function=launch_setup,
113+
args=context_arguments
114+
)
115+
116+
ld.add_action(opq_function)
117+
118+
return ld

0 commit comments

Comments
 (0)