forked from Myzhar/ldrobot-lidar-ros2
-
Notifications
You must be signed in to change notification settings - Fork 0
/
Copy pathldlidar.launch.py
79 lines (61 loc) · 1.98 KB
/
ldlidar.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
73
74
75
76
77
78
79
#!/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, LifecycleNode
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')
# Lidar node configuration file
lidar_config_path = os.path.join(
get_package_share_directory('ldlidar_node'),
'config',
'ldlidar.yaml'
)
# Launch arguments
declare_node_name_cmd = DeclareLaunchArgument(
'node_name',
default_value='ldlidar_node',
description='Name of the node'
)
# LDLidar lifecycle node
ldlidar_node = LifecycleNode(
package = 'ldlidar_node',
executable = 'ldlidar_node',
name = node_name,
output='screen',
parameters=[
# YAML files
lidar_config_path # Parameters
]
)
# URDF path
urdf_file_name = 'ldlidar_descr.urdf.xml'
urdf = os.path.join(
get_package_share_directory('ldlidar_node'),
'urdf',
urdf_file_name)
with open(urdf, 'r') as infp:
robot_desc = infp.read()
# Robot State Publisher node
rsp_node = Node(
package='robot_state_publisher',
executable='robot_state_publisher',
name='ldlidar_state_publisher',
output='screen',
parameters=[{'robot_description': robot_desc}],
arguments=[urdf]
)
# Define LaunchDescription variable
ld = LaunchDescription()
# Launch arguments
ld.add_action(declare_node_name_cmd)
# Launch Nav2 Lifecycle Manager
ld.add_action(rsp_node)
# LDLidar Lifecycle node
ld.add_action(ldlidar_node)
return ld