Skip to content

Commit 1459dd9

Browse files
committed
further fixes
1 parent e10a053 commit 1459dd9

File tree

2 files changed

+266
-230
lines changed

2 files changed

+266
-230
lines changed

launch/navigation.launch.py

+135-128
Original file line numberDiff line numberDiff line change
@@ -21,143 +21,150 @@
2121
2222
1. `ros2 launch neo_simulation2 navigation.launch.py --show-args`
2323
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`
24+
2. `ros2 launch neo_simulation2 navigation.launch.py map_name:=neo_track1 use_sim_time:=True use_multi_robots:=False use_amcl:=False`
2525
This command launches the simulation with sample values for the arguments.
2626
!(case is important for True/False)
2727
2828
"""
2929

3030
# OpaqueFunction is used to perform setup actions during launch through a Python function
3131
def launch_setup(context: LaunchContext,
32-
my_neo_robot_arg, my_neo_env_arg, use_sim_time_arg,
33-
use_amcl_arg, use_multi_robots_arg, namespace_arg,
34-
param_file_arg):
35-
36-
my_neo_robot = my_neo_robot_arg.perform(context)
37-
my_neo_environment = my_neo_env_arg.perform(context)
38-
use_sim_time = use_sim_time_arg.perform(context)
39-
use_amcl = use_amcl_arg.perform(context)
40-
use_multi_robots = use_multi_robots_arg.perform(context)
41-
namespace = namespace_arg.perform(context)
42-
param_dir = param_file_arg.perform(context)
43-
44-
# Only set path for the neobotix supported maps
45-
if (my_neo_environment == "neo_workshop" or my_neo_environment == "neo_track1"):
46-
map_dir = os.path.join(
47-
get_package_share_directory('neo_simulation2'),
48-
'maps',
49-
my_neo_environment+'.yaml')
50-
else:
51-
map_dir = my_neo_environment
52-
53-
launch_actions = []
54-
55-
nav2_launch_file_dir = os.path.join(get_package_share_directory('neo_nav2_bringup'), 'launch')
56-
57-
# Define the IncludeLaunchDescription objects
58-
# neo_localization
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-
# amcl_localization
71-
localization_amcl_launch_description = IncludeLaunchDescription(
72-
PythonLaunchDescriptionSource([nav2_launch_file_dir, '/localization_amcl.launch.py']),
73-
condition=IfCondition(use_amcl),
74-
launch_arguments={
75-
'map': map_dir,
76-
'use_sim_time': use_sim_time,
77-
'use_multi_robots': use_multi_robots,
78-
'params_file': param_dir,
79-
'namespace': namespace}.items(),
80-
)
81-
82-
# starting the navigation
83-
navigation_neo_launch_description = IncludeLaunchDescription(
84-
PythonLaunchDescriptionSource([nav2_launch_file_dir, '/navigation_neo.launch.py']),
85-
launch_arguments={
86-
'namespace': namespace,
87-
'use_sim_time': use_sim_time,
88-
'params_file': param_dir}.items(),
89-
)
90-
91-
# Append the IncludeLaunchDescription objects to the launch_actions list
92-
launch_actions.append(localization_neo_launch_description)
93-
launch_actions.append(localization_amcl_launch_description)
94-
launch_actions.append(navigation_neo_launch_description)
95-
96-
return launch_actions
32+
my_neo_env_arg, use_sim_time_arg,
33+
use_amcl_arg, use_multi_robots_arg, namespace_arg,
34+
param_file_arg):
35+
36+
my_neo_environment = my_neo_env_arg.perform(context)
37+
use_sim_time = use_sim_time_arg.perform(context)
38+
use_amcl = use_amcl_arg.perform(context)
39+
use_multi_robots = use_multi_robots_arg.perform(context)
40+
namespace = namespace_arg.perform(context)
41+
param_dir = param_file_arg.perform(context)
42+
43+
robots = ["mpo_700", "mp_400", "mp_500", "mpo_500"]
44+
45+
# Reading the selected robot from robot_name.txt
46+
with open('robot_name.txt', 'r') as file:
47+
my_neo_robot = file.read()
48+
49+
if (param_dir == ""):
50+
for robot in robots:
51+
if (my_neo_robot == robot):
52+
param_dir = os.path.join(
53+
get_package_share_directory('neo_simulation2'),
54+
'configs/' + my_neo_robot,
55+
'navigation.yaml')
56+
break
57+
58+
# Only set path for the neobotix supported maps
59+
if (my_neo_environment == "neo_workshop" or my_neo_environment == "neo_track1"):
60+
map_dir = os.path.join(
61+
get_package_share_directory('neo_simulation2'),
62+
'maps',
63+
my_neo_environment+'.yaml')
64+
else:
65+
map_dir = my_neo_environment
66+
67+
launch_actions = []
68+
69+
nav2_launch_file_dir = os.path.join(get_package_share_directory('neo_nav2_bringup'), 'launch')
70+
71+
# Define the IncludeLaunchDescription objects
72+
# neo_localization
73+
localization_neo_launch_description = IncludeLaunchDescription(
74+
PythonLaunchDescriptionSource([nav2_launch_file_dir, '/localization_neo.launch.py']),
75+
condition=IfCondition(PythonExpression(['not ', use_amcl])),
76+
launch_arguments={
77+
'map': map_dir,
78+
'use_sim_time': use_sim_time,
79+
'use_multi_robots': use_multi_robots,
80+
'params_file': param_dir,
81+
'namespace': namespace}.items(),
82+
)
83+
84+
# amcl_localization
85+
localization_amcl_launch_description = IncludeLaunchDescription(
86+
PythonLaunchDescriptionSource([nav2_launch_file_dir, '/localization_amcl.launch.py']),
87+
condition=IfCondition(use_amcl),
88+
launch_arguments={
89+
'map': map_dir,
90+
'use_sim_time': use_sim_time,
91+
'use_multi_robots': use_multi_robots,
92+
'params_file': param_dir,
93+
'namespace': namespace}.items(),
94+
)
95+
96+
# starting the navigation
97+
navigation_neo_launch_description = IncludeLaunchDescription(
98+
PythonLaunchDescriptionSource([nav2_launch_file_dir, '/navigation_neo.launch.py']),
99+
launch_arguments={
100+
'namespace': namespace,
101+
'use_sim_time': use_sim_time,
102+
'params_file': param_dir}.items(),
103+
)
104+
105+
# Append the IncludeLaunchDescription objects to the launch_actions list
106+
launch_actions.append(localization_neo_launch_description)
107+
launch_actions.append(localization_amcl_launch_description)
108+
launch_actions.append(navigation_neo_launch_description)
109+
110+
return launch_actions
97111

98112
def generate_launch_description():
99-
ld = LaunchDescription()
100-
101-
# Declare launch arguments 'my_robot' and 'map_name' with default values and descriptions
102-
declare_my_robot_arg = DeclareLaunchArgument(
103-
'my_robot', default_value='mpo_700',
104-
description='Robot Types: "mpo_700", "mpo_500", "mp_400", "mp_500"'
105-
)
106-
107-
declare_map_name_arg = DeclareLaunchArgument(
108-
'map', default_value='neo_workshop',
109-
description='Available maps: "neo_track1", "neo_workshop" or specify full path to your map'
110-
)
111-
112-
declare_use_multi_robots_cmd = DeclareLaunchArgument(
113-
'use_multi_robots', default_value='False',
114-
description='Use multi robots "True/False"'
115-
)
116-
117-
declare_param_file_arg = DeclareLaunchArgument(
118-
'param_file', default_value=os.path.join(
119-
get_package_share_directory('neo_simulation2'),
120-
'configs/mpo_700',
121-
'navigation.yaml'),
122-
description='Param file that needs to be used for navigation'
123-
)
124-
125-
declare_use_amcl_cmd = DeclareLaunchArgument(
126-
'use_amcl', default_value='False',
127-
description='Use amcl for localization "True/False"'
128-
)
129-
130-
declare_use_sim_time_cmd = DeclareLaunchArgument(
131-
'use_sim_time', default_value='True',
132-
description='Use simulation clock if true "True/False"'
133-
)
134-
135-
declare_namespace_cmd = DeclareLaunchArgument(
136-
'robot_namespace', default_value='',
137-
description='Top-level namespace'
138-
)
139-
140-
# Create launch configuration variables for the launch arguments
141-
my_neo_robot_arg = LaunchConfiguration('my_robot')
142-
my_neo_env_arg = LaunchConfiguration('map')
143-
use_multi_robots = LaunchConfiguration('use_multi_robots')
144-
use_amcl = LaunchConfiguration('use_amcl')
145-
use_sim_time = LaunchConfiguration('use_sim_time')
146-
namespace = LaunchConfiguration('robot_namespace')
147-
params_file = LaunchConfiguration('param_file')
148-
149-
ld.add_action(declare_my_robot_arg)
150-
ld.add_action(declare_map_name_arg)
151-
ld.add_action(declare_param_file_arg)
152-
ld.add_action(declare_use_multi_robots_cmd)
153-
ld.add_action(declare_use_amcl_cmd)
154-
ld.add_action(declare_use_sim_time_cmd)
155-
ld.add_action(declare_namespace_cmd)
156-
157-
context_arguments = [my_neo_robot_arg, my_neo_env_arg, use_sim_time, use_amcl, use_multi_robots, namespace, params_file]
158-
opq_func = OpaqueFunction(function = launch_setup,
113+
ld = LaunchDescription()
114+
115+
# Declare launch arguments 'my_robot' and 'map_name' with default values and descriptions
116+
declare_map_name_arg = DeclareLaunchArgument(
117+
'map', default_value='neo_workshop',
118+
description='Available maps: "neo_track1", "neo_workshop" or specify full path to your map'
119+
)
120+
121+
declare_use_multi_robots_cmd = DeclareLaunchArgument(
122+
'use_multi_robots', default_value='False',
123+
description='Use multi robots "True/False"'
124+
)
125+
126+
declare_param_file_arg = DeclareLaunchArgument(
127+
'param_file',
128+
default_value="",
129+
description='Param file that needs to be used for navigation, sets according to robot by default'
130+
)
131+
132+
declare_use_amcl_cmd = DeclareLaunchArgument(
133+
'use_amcl',
134+
default_value='False',
135+
description='Use amcl for localization "True/False"'
136+
)
137+
138+
declare_use_sim_time_cmd = DeclareLaunchArgument(
139+
'use_sim_time',
140+
default_value='True',
141+
description='Use simulation clock if true "True/False"'
142+
)
143+
144+
declare_namespace_cmd = DeclareLaunchArgument(
145+
'robot_namespace', default_value='',
146+
description='Top-level namespace'
147+
)
148+
149+
# Create launch configuration variables for the launch arguments
150+
my_neo_env_arg = LaunchConfiguration('map')
151+
use_multi_robots = LaunchConfiguration('use_multi_robots')
152+
use_amcl = LaunchConfiguration('use_amcl')
153+
use_sim_time = LaunchConfiguration('use_sim_time')
154+
namespace = LaunchConfiguration('robot_namespace')
155+
params_file = LaunchConfiguration('param_file')
156+
157+
ld.add_action(declare_map_name_arg)
158+
ld.add_action(declare_param_file_arg)
159+
ld.add_action(declare_use_multi_robots_cmd)
160+
ld.add_action(declare_use_amcl_cmd)
161+
ld.add_action(declare_use_sim_time_cmd)
162+
ld.add_action(declare_namespace_cmd)
163+
164+
context_arguments = [my_neo_env_arg, use_sim_time, use_amcl, use_multi_robots, namespace, params_file]
165+
opq_func = OpaqueFunction(function = launch_setup,
159166
args = context_arguments)
160167

161-
ld.add_action(opq_func)
168+
ld.add_action(opq_func)
162169

163-
return ld
170+
return ld

0 commit comments

Comments
 (0)