forked from Myzhar/ldrobot-lidar-ros2
-
Notifications
You must be signed in to change notification settings - Fork 0
/
Copy pathldlidar_with_mgr.launch.py
72 lines (56 loc) · 1.91 KB
/
ldlidar_with_mgr.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
63
64
65
66
67
68
69
70
71
72
#!/usr/bin/env python3
import os
from ament_index_python.packages import get_package_share_directory
from launch import LaunchDescription
from launch.actions import DeclareLaunchArgument
from launch.substitutions import LaunchConfiguration, Command
from launch_ros.actions import Node
from launch.actions import IncludeLaunchDescription
from launch.launch_description_sources import PythonLaunchDescriptionSource
def generate_launch_description():
# Set LOG format
os.environ['RCUTILS_CONSOLE_OUTPUT_FORMAT'] = '{time} [{severity}] ({name}) {message}'
os.environ['RCUTILS_COLORIZED_OUTPUT'] = '1'
node_name = LaunchConfiguration('node_name')
# Lifecycle manager configuration file
lc_mgr_config_path = os.path.join(
get_package_share_directory('ldlidar_node'),
'config',
'lifecycle_mgr.yaml'
)
# Launch arguments
declare_node_name_cmd = DeclareLaunchArgument(
'node_name',
default_value='ldlidar_node',
description='Name of the node'
)
# Lifecycle manager node
lc_mgr_node = Node(
package='nav2_lifecycle_manager',
executable='lifecycle_manager',
name='lifecycle_manager',
output='screen',
parameters=[
# YAML files
lc_mgr_config_path # Parameters
]
)
# Include LDLidar launch
ldlidar_launch = IncludeLaunchDescription(
launch_description_source=PythonLaunchDescriptionSource([
get_package_share_directory('ldlidar_node'),
'/launch/ldlidar.launch.py'
]),
launch_arguments={
'node_name': node_name
}.items()
)
# Define LaunchDescription variable
ld = LaunchDescription()
# Launch arguments
ld.add_action(declare_node_name_cmd)
# Launch Nav2 Lifecycle Manager
ld.add_action(lc_mgr_node)
# Call LDLidar launch
ld.add_action(ldlidar_launch)
return ld