-
Notifications
You must be signed in to change notification settings - Fork 1.8k
/
Copy pathrs_launch.py
157 lines (151 loc) · 12.3 KB
/
rs_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
80
81
82
83
84
85
86
87
88
89
90
91
92
93
94
95
96
97
98
99
100
101
102
103
104
105
106
107
108
109
110
111
112
113
114
115
116
117
118
119
120
121
122
123
124
125
126
127
128
129
130
131
132
133
134
135
136
137
138
139
140
141
142
143
144
145
146
147
148
149
150
151
152
153
154
155
156
157
# Copyright (c) 2018 Intel Corporation
#
# Licensed under the Apache License, Version 2.0 (the "License");
# you may not use this file except in compliance with the License.
# You may obtain a copy of the License at
#
# http://www.apache.org/licenses/LICENSE-2.0
#
# Unless required by applicable law or agreed to in writing, software
# distributed under the License is distributed on an "AS IS" BASIS,
# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
# See the License for the specific language governing permissions and
# limitations under the License.
"""Launch realsense2_camera node."""
import os
from launch import LaunchDescription
from ament_index_python.packages import get_package_share_directory
import launch_ros.actions
from launch.actions import DeclareLaunchArgument
from launch.substitutions import LaunchConfiguration, PythonExpression
from launch.conditions import IfCondition
configurable_parameters = [{'name': 'camera_name', 'default': 'camera', 'description': 'camera unique name'},
{'name': 'serial_no', 'default': "''", 'description': 'choose device by serial number'},
{'name': 'usb_port_id', 'default': "''", 'description': 'choose device by usb port id'},
{'name': 'device_type', 'default': "''", 'description': 'choose device by type'},
{'name': 'config_file', 'default': "''", 'description': 'yaml config file'},
{'name': 'enable_pointcloud', 'default': 'false', 'description': 'enable pointcloud'},
{'name': 'unite_imu_method', 'default': "''", 'description': '[copy|linear_interpolation]'},
{'name': 'json_file_path', 'default': "''", 'description': 'allows advanced configuration'},
{'name': 'log_level', 'default': 'info', 'description': 'debug log level [DEBUG|INFO|WARN|ERROR|FATAL]'},
{'name': 'output', 'default': 'screen', 'description': 'pipe node output [screen|log]'},
{'name': 'depth_width', 'default': '-1', 'description': 'depth image width'},
{'name': 'depth_height', 'default': '-1', 'description': 'depth image height'},
{'name': 'enable_depth', 'default': 'true', 'description': 'enable depth stream'},
{'name': 'color_width', 'default': '-1', 'description': 'color image width'},
{'name': 'color_height', 'default': '-1', 'description': 'color image height'},
{'name': 'enable_color', 'default': 'true', 'description': 'enable color stream'},
{'name': 'infra_width', 'default': '-1', 'description': 'infra width'},
{'name': 'infra_height', 'default': '-1', 'description': 'infra width'},
{'name': 'enable_infra1', 'default': 'true', 'description': 'enable infra1 stream'},
{'name': 'enable_infra2', 'default': 'true', 'description': 'enable infra2 stream'},
{'name': 'infra_rgb', 'default': 'false', 'description': 'enable infra2 stream'},
{'name': 'fisheye_width', 'default': '-1', 'description': 'fisheye width'},
{'name': 'fisheye_height', 'default': '-1', 'description': 'fisheye width'},
{'name': 'enable_fisheye1', 'default': 'true', 'description': 'enable fisheye1 stream'},
{'name': 'enable_fisheye2', 'default': 'true', 'description': 'enable fisheye2 stream'},
{'name': 'confidence_width', 'default': '-1', 'description': 'depth image width'},
{'name': 'confidence_height', 'default': '-1', 'description': 'depth image height'},
{'name': 'enable_confidence', 'default': 'true', 'description': 'enable depth stream'},
{'name': 'fisheye_fps', 'default': '-1.', 'description': ''},
{'name': 'depth_fps', 'default': '-1.', 'description': ''},
{'name': 'confidence_fps', 'default': '-1.', 'description': ''},
{'name': 'infra_fps', 'default': '-1.', 'description': ''},
{'name': 'color_fps', 'default': '-1.', 'description': ''},
{'name': 'gyro_fps', 'default': '-1.', 'description': ''},
{'name': 'accel_fps', 'default': '-1.', 'description': ''},
{'name': 'color_qos', 'default': 'SYSTEM_DEFAULT', 'description': 'QoS profile name'},
{'name': 'confidence_qos', 'default': 'SYSTEM_DEFAULT', 'description': 'QoS profile name'},
{'name': 'depth_qos', 'default': 'SYSTEM_DEFAULT', 'description': 'QoS profile name'},
{'name': 'fisheye_qos', 'default': 'SYSTEM_DEFAULT', 'description': 'QoS profile name'},
{'name': 'infra_qos', 'default': 'SYSTEM_DEFAULT', 'description': 'QoS profile name'},
{'name': 'pointcloud_qos', 'default': 'SYSTEM_DEFAULT', 'description': 'QoS profile name'},
{'name': 'enable_gyro', 'default': 'false', 'description': ''},
{'name': 'enable_accel', 'default': 'false', 'description': ''},
{'name': 'pointcloud_texture_stream', 'default': 'RS2_STREAM_COLOR', 'description': 'testure stream for pointcloud'},
{'name': 'pointcloud_texture_index', 'default': '0', 'description': 'testure stream index for pointcloud'},
{'name': 'enable_sync', 'default': 'false', 'description': ''},
{'name': 'align_depth', 'default': 'false', 'description': ''},
{'name': 'filters', 'default': "''", 'description': ''},
{'name': 'clip_distance', 'default': '-2.', 'description': ''},
{'name': 'linear_accel_cov', 'default': '0.01', 'description': ''},
{'name': 'initial_reset', 'default': 'false', 'description': ''},
{'name': 'allow_no_texture_points', 'default': 'false', 'description': ''},
{'name': 'ordered_pc', 'default': 'false', 'description': ''},
{'name': 'calib_odom_file', 'default': "''", 'description': "''"},
{'name': 'topic_odom_in', 'default': "''", 'description': 'topic for T265 wheel odometry'},
{'name': 'tf_publish_rate', 'default': '0.0', 'description': 'Rate of publishing static_tf'},
{'name': 'diagnostics_period', 'default': '0.0', 'description': 'Rate of publishing diagnostics. 0=Disabled'},
{'name': 'rosbag_filename', 'default': "''", 'description': 'A realsense bagfile to run from as a device'},
{'name': 'temporal.holes_fill', 'default': '0', 'description': 'Persistency mode'},
{'name': 'stereo_module.exposure.1', 'default': '7500', 'description': 'Initial value for hdr_merge filter'},
{'name': 'stereo_module.gain.1', 'default': '16', 'description': 'Initial value for hdr_merge filter'},
{'name': 'stereo_module.exposure.2', 'default': '1', 'description': 'Initial value for hdr_merge filter'},
{'name': 'stereo_module.gain.2', 'default': '16', 'description': 'Initial value for hdr_merge filter'},
{'name': 'wait_for_device_timeout', 'default': '-1.', 'description': 'Timeout for waiting for device to connect (Seconds)'},
{'name': 'reconnect_timeout', 'default': '6.', 'description': 'Timeout(seconds) between consequtive reconnection attempts'},
]
def declare_configurable_parameters(parameters):
return [DeclareLaunchArgument(param['name'], default_value=param['default'], description=param['description']) for param in parameters]
def set_configurable_parameters(parameters):
return dict([(param['name'], LaunchConfiguration(param['name'])) for param in parameters])
def generate_launch_description():
log_level = 'info'
if (os.getenv('ROS_DISTRO') == "dashing") or (os.getenv('ROS_DISTRO') == "eloquent"):
return LaunchDescription(declare_configurable_parameters(configurable_parameters) + [
# Realsense
launch_ros.actions.Node(
condition=IfCondition(PythonExpression([LaunchConfiguration('config_file'), " == ''"])),
package='realsense2_camera',
node_namespace=LaunchConfiguration("camera_name"),
node_name=LaunchConfiguration("camera_name"),
node_executable='realsense2_camera_node',
prefix=['stdbuf -o L'],
parameters=[set_configurable_parameters(configurable_parameters)
],
output='screen',
arguments=['--ros-args', '--log-level', LaunchConfiguration('log_level')],
),
launch_ros.actions.Node(
condition=IfCondition(PythonExpression([LaunchConfiguration('config_file'), " != ''"])),
package='realsense2_camera',
node_namespace=LaunchConfiguration("camera_name"),
node_name=LaunchConfiguration("camera_name"),
node_executable='realsense2_camera_node',
prefix=['stdbuf -o L'],
parameters=[set_configurable_parameters(configurable_parameters)
, PythonExpression([LaunchConfiguration("config_file")])
],
output='screen',
arguments=['--ros-args', '--log-level', LaunchConfiguration('log_level')],
),
])
else:
return LaunchDescription(declare_configurable_parameters(configurable_parameters) + [
# Realsense
launch_ros.actions.Node(
condition=IfCondition(PythonExpression([LaunchConfiguration('config_file'), " == ''"])),
package='realsense2_camera',
namespace=LaunchConfiguration("camera_name"),
name=LaunchConfiguration("camera_name"),
executable='realsense2_camera_node',
parameters=[set_configurable_parameters(configurable_parameters)
],
output='screen',
arguments=['--ros-args', '--log-level', LaunchConfiguration('log_level')],
emulate_tty=True,
),
launch_ros.actions.Node(
condition=IfCondition(PythonExpression([LaunchConfiguration('config_file'), " != ''"])),
package='realsense2_camera',
namespace=LaunchConfiguration("camera_name"),
name=LaunchConfiguration("camera_name"),
executable='realsense2_camera_node',
parameters=[set_configurable_parameters(configurable_parameters)
, PythonExpression([LaunchConfiguration("config_file")])
],
output='screen',
arguments=['--ros-args', '--log-level', LaunchConfiguration('log_level')],
emulate_tty=True,
),
])