-
Notifications
You must be signed in to change notification settings - Fork 28
/
online_async_launch.py
62 lines (48 loc) · 2.43 KB
/
online_async_launch.py
1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
33
34
35
36
37
38
39
40
41
42
43
44
45
46
47
48
49
50
51
52
53
54
55
56
57
58
59
60
61
62
import os
from launch import LaunchDescription
from launch.actions import DeclareLaunchArgument, LogInfo
from launch.conditions import UnlessCondition
from launch.substitutions import LaunchConfiguration, PythonExpression
from launch_ros.actions import Node
from ament_index_python.packages import get_package_share_directory
from nav2_common.launch import HasNodeParams
def generate_launch_description():
use_sim_time = LaunchConfiguration('use_sim_time')
slam_params_file = LaunchConfiguration('slam_params_file')
default_params_file = os.path.join(get_package_share_directory('lidarbot_slam'),
'config', 'mapper_params_online_async.yaml')
declare_use_sim_time_argument = DeclareLaunchArgument(
'use_sim_time',
default_value='true',
description='Use simulation/Gazebo clock')
declare_params_file_cmd = DeclareLaunchArgument(
'slam_params_file',
default_value=default_params_file,
description='Full path to the ROS2 parameters file to use for the slam_toolbox node')
# If the provided param file doesn't have slam_toolbox params, we must pass the
# default_params_file instead. This could happen due to automatic propagation of
# LaunchArguments. See:
# https://github.com/ros-planning/navigation2/pull/2243#issuecomment-800479866
has_node_params = HasNodeParams(source_file=slam_params_file,
node_name='slam_toolbox')
actual_params_file = PythonExpression(['"', slam_params_file, '" if ', has_node_params,
' else "', default_params_file, '"'])
log_param_change = LogInfo(msg=['provided params_file ', slam_params_file,
' does not contain slam_toolbox parameters. Using default: ',
default_params_file],
condition=UnlessCondition(has_node_params))
start_async_slam_toolbox_node = Node(
parameters=[
actual_params_file,
{'use_sim_time': use_sim_time}
],
package='slam_toolbox',
executable='async_slam_toolbox_node',
name='slam_toolbox',
output='screen')
ld = LaunchDescription()
ld.add_action(declare_use_sim_time_argument)
ld.add_action(declare_params_file_cmd)
ld.add_action(log_param_change)
ld.add_action(start_async_slam_toolbox_node)
return ld