forked from IntelRealSense/realsense-ros
-
Notifications
You must be signed in to change notification settings - Fork 0
/
nodelet.launch.xml
181 lines (155 loc) · 11.9 KB
/
nodelet.launch.xml
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
158
159
160
161
162
163
164
165
166
167
168
169
170
171
172
173
174
175
176
177
178
179
180
181
<launch>
<arg name="external_manager" default="false"/>
<arg name="manager" default="realsense2_camera_manager"/>
<arg name="serial_no" default=""/>
<arg name="usb_port_id" default=""/>
<arg name="device_type" default=""/>
<arg name="tf_prefix" default=""/>
<arg name="json_file_path" default=""/>
<arg name="rosbag_filename" default=""/>
<arg name="required" default="false"/>
<arg name="fisheye_width" default="0"/>
<arg name="fisheye_height" default="0"/>
<arg name="enable_fisheye" default="true"/>
<arg name="enable_fisheye1" default="true"/>
<arg name="enable_fisheye2" default="true"/>
<arg name="depth_width" default="640"/>
<arg name="depth_height" default="480"/>
<arg name="enable_depth" default="true"/>
<arg name="infra_width" default="640"/>
<arg name="infra_height" default="480"/>
<arg name="enable_infra1" default="true"/>
<arg name="enable_infra2" default="true"/>
<arg name="color_width" default="640"/>
<arg name="color_height" default="480"/>
<arg name="enable_color" default="true"/>
<arg name="fisheye_fps" default="30"/>
<arg name="depth_fps" default="30"/>
<arg name="infra_fps" default="30"/>
<arg name="color_fps" default="30"/>
<arg name="gyro_fps" default="0"/>
<arg name="accel_fps" default="0"/>
<arg name="enable_gyro" default="true"/>
<arg name="enable_accel" default="true"/>
<arg name="enable_pointcloud" default="false"/>
<arg name="pointcloud_texture_stream" default="RS2_STREAM_COLOR"/> <!-- use RS2_STREAM_ANY to avoid using texture -->
<arg name="pointcloud_texture_index" default="0"/>
<arg name="enable_sync" default="false"/>
<arg name="align_depth" default="false"/>
<arg name="base_frame_id" default="$(arg tf_prefix)_link"/>
<arg name="depth_frame_id" default="$(arg tf_prefix)_depth_frame"/>
<arg name="infra1_frame_id" default="$(arg tf_prefix)_infra1_frame"/>
<arg name="infra2_frame_id" default="$(arg tf_prefix)_infra2_frame"/>
<arg name="color_frame_id" default="$(arg tf_prefix)_color_frame"/>
<arg name="fisheye_frame_id" default="$(arg tf_prefix)_fisheye_frame"/>
<arg name="fisheye1_frame_id" default="$(arg tf_prefix)_fisheye1_frame"/>
<arg name="fisheye2_frame_id" default="$(arg tf_prefix)_fisheye2_frame"/>
<arg name="accel_frame_id" default="$(arg tf_prefix)_accel_frame"/>
<arg name="gyro_frame_id" default="$(arg tf_prefix)_gyro_frame"/>
<arg name="pose_frame_id" default="$(arg tf_prefix)_pose_frame"/>
<arg name="depth_optical_frame_id" default="$(arg tf_prefix)_depth_optical_frame"/>
<arg name="infra1_optical_frame_id" default="$(arg tf_prefix)_infra1_optical_frame"/>
<arg name="infra2_optical_frame_id" default="$(arg tf_prefix)_infra2_optical_frame"/>
<arg name="color_optical_frame_id" default="$(arg tf_prefix)_color_optical_frame"/>
<arg name="fisheye_optical_frame_id" default="$(arg tf_prefix)_fisheye_optical_frame"/>
<arg name="fisheye1_optical_frame_id" default="$(arg tf_prefix)_fisheye1_optical_frame"/>
<arg name="fisheye2_optical_frame_id" default="$(arg tf_prefix)_fisheye2_optical_frame"/>
<arg name="accel_optical_frame_id" default="$(arg tf_prefix)_accel_optical_frame"/>
<arg name="gyro_optical_frame_id" default="$(arg tf_prefix)_gyro_optical_frame"/>
<arg name="imu_optical_frame_id" default="$(arg tf_prefix)_imu_optical_frame"/>
<arg name="pose_optical_frame_id" default="$(arg tf_prefix)_pose_optical_frame"/>
<arg name="aligned_depth_to_color_frame_id" default="$(arg tf_prefix)_aligned_depth_to_color_frame"/>
<arg name="aligned_depth_to_infra1_frame_id" default="$(arg tf_prefix)_aligned_depth_to_infra1_frame"/>
<arg name="aligned_depth_to_infra2_frame_id" default="$(arg tf_prefix)_aligned_depth_to_infra2_frame"/>
<arg name="aligned_depth_to_fisheye_frame_id" default="$(arg tf_prefix)_aligned_depth_to_fisheye_frame"/>
<arg name="aligned_depth_to_fisheye1_frame_id" default="$(arg tf_prefix)_aligned_depth_to_fisheye1_frame"/>
<arg name="aligned_depth_to_fisheye2_frame_id" default="$(arg tf_prefix)_aligned_depth_to_fisheye2_frame"/>
<arg name="publish_tf" default="true"/>
<arg name="tf_publish_rate" default="0"/> <!-- 0 - static transform -->
<arg name="odom_frame_id" default="$(arg tf_prefix)_odom_frame"/>
<arg name="topic_odom_in" default="$(arg tf_prefix)/odom_in"/>
<arg name="calib_odom_file" default=""/>
<arg name="publish_odom_tf" default="true"/>
<arg name="filters" default=""/>
<arg name="clip_distance" default="-1"/>
<arg name="linear_accel_cov" default="0.01"/>
<arg name="initial_reset" default="false"/>
<arg name="unite_imu_method" default="none"/> <!-- Options are: [none, copy, linear_interpolation] -->
<arg name="allow_no_texture_points" default="false"/>
<node unless="$(arg external_manager)" pkg="nodelet" type="nodelet" name="$(arg manager)" args="manager" output="screen" required="$(arg required)"/>
<node pkg="nodelet" type="nodelet" name="realsense2_camera" args="load realsense2_camera/RealSenseNodeFactory $(arg manager)" required="$(arg required)">
<param name="serial_no" type="str" value="$(arg serial_no)"/>
<param name="usb_port_id" type="str" value="$(arg usb_port_id)"/>
<param name="device_type" type="str" value="$(arg device_type)"/>
<param name="json_file_path" type="str" value="$(arg json_file_path)"/>
<param name="rosbag_filename" type="str" value="$(arg rosbag_filename)"/>
<param name="enable_pointcloud" type="bool" value="$(arg enable_pointcloud)"/>
<param name="pointcloud_texture_stream" type="str" value="$(arg pointcloud_texture_stream)"/>
<param name="pointcloud_texture_index" type="int" value="$(arg pointcloud_texture_index)"/>
<param name="enable_sync" type="bool" value="$(arg enable_sync)"/>
<param name="align_depth" type="bool" value="$(arg align_depth)"/>
<param name="fisheye_width" type="int" value="$(arg fisheye_width)"/>
<param name="fisheye_height" type="int" value="$(arg fisheye_height)"/>
<param name="enable_fisheye" type="bool" value="$(arg enable_fisheye)"/>
<param name="enable_fisheye1" type="bool" value="$(arg enable_fisheye1)"/>
<param name="enable_fisheye2" type="bool" value="$(arg enable_fisheye2)"/>
<param name="depth_width" type="int" value="$(arg depth_width)"/>
<param name="depth_height" type="int" value="$(arg depth_height)"/>
<param name="enable_depth" type="bool" value="$(arg enable_depth)"/>
<param name="color_width" type="int" value="$(arg color_width)"/>
<param name="color_height" type="int" value="$(arg color_height)"/>
<param name="enable_color" type="bool" value="$(arg enable_color)"/>
<param name="infra_width" type="int" value="$(arg infra_width)"/>
<param name="infra_height" type="int" value="$(arg infra_height)"/>
<param name="enable_infra1" type="bool" value="$(arg enable_infra1)"/>
<param name="enable_infra2" type="bool" value="$(arg enable_infra2)"/>
<param name="fisheye_fps" type="int" value="$(arg fisheye_fps)"/>
<param name="depth_fps" type="int" value="$(arg depth_fps)"/>
<param name="infra_fps" type="int" value="$(arg infra_fps)"/>
<param name="color_fps" type="int" value="$(arg color_fps)"/>
<param name="gyro_fps" type="int" value="$(arg gyro_fps)"/>
<param name="accel_fps" type="int" value="$(arg accel_fps)"/>
<param name="enable_gyro" type="bool" value="$(arg enable_gyro)"/>
<param name="enable_accel" type="bool" value="$(arg enable_accel)"/>
<param name="base_frame_id" type="str" value="$(arg base_frame_id)"/>
<param name="depth_frame_id" type="str" value="$(arg depth_frame_id)"/>
<param name="infra1_frame_id" type="str" value="$(arg infra1_frame_id)"/>
<param name="infra2_frame_id" type="str" value="$(arg infra2_frame_id)"/>
<param name="color_frame_id" type="str" value="$(arg color_frame_id)"/>
<param name="fisheye_frame_id" type="str" value="$(arg fisheye_frame_id)"/>
<param name="fisheye1_frame_id" type="str" value="$(arg fisheye1_frame_id)"/>
<param name="fisheye2_frame_id" type="str" value="$(arg fisheye2_frame_id)"/>
<param name="accel_frame_id" type="str" value="$(arg accel_frame_id)"/>
<param name="gyro_frame_id" type="str" value="$(arg gyro_frame_id)"/>
<param name="pose_frame_id" type="str" value="$(arg pose_frame_id)"/>
<param name="depth_optical_frame_id" type="str" value="$(arg depth_optical_frame_id)"/>
<param name="infra1_optical_frame_id" type="str" value="$(arg infra1_optical_frame_id)"/>
<param name="infra2_optical_frame_id" type="str" value="$(arg infra2_optical_frame_id)"/>
<param name="color_optical_frame_id" type="str" value="$(arg color_optical_frame_id)"/>
<param name="fisheye_optical_frame_id" type="str" value="$(arg fisheye_optical_frame_id)"/>
<param name="fisheye1_optical_frame_id" type="str" value="$(arg fisheye1_optical_frame_id)"/>
<param name="fisheye2_optical_frame_id" type="str" value="$(arg fisheye2_optical_frame_id)"/>
<param name="accel_optical_frame_id" type="str" value="$(arg accel_optical_frame_id)"/>
<param name="gyro_optical_frame_id" type="str" value="$(arg gyro_optical_frame_id)"/>
<param name="imu_optical_frame_id" type="str" value="$(arg imu_optical_frame_id)"/>
<param name="pose_optical_frame_id" type="str" value="$(arg pose_optical_frame_id)"/>
<param name="aligned_depth_to_color_frame_id" type="str" value="$(arg aligned_depth_to_color_frame_id)"/>
<param name="aligned_depth_to_infra1_frame_id" type="str" value="$(arg aligned_depth_to_infra1_frame_id)"/>
<param name="aligned_depth_to_infra2_frame_id" type="str" value="$(arg aligned_depth_to_infra2_frame_id)"/>
<param name="aligned_depth_to_fisheye_frame_id" type="str" value="$(arg aligned_depth_to_fisheye_frame_id)"/>
<param name="aligned_depth_to_fisheye1_frame_id" type="str" value="$(arg aligned_depth_to_fisheye1_frame_id)"/>
<param name="aligned_depth_to_fisheye2_frame_id" type="str" value="$(arg aligned_depth_to_fisheye2_frame_id)"/>
<param name="publish_tf" type="bool" value="$(arg publish_tf)"/>
<param name="tf_publish_rate" type="double" value="$(arg tf_publish_rate)"/>
<param name="odom_frame_id" type="str" value="$(arg odom_frame_id)"/>
<param name="topic_odom_in" type="str" value="$(arg topic_odom_in)"/>
<param name="calib_odom_file" type="str" value="$(arg calib_odom_file)"/>
<param name="publish_odom_tf" type="bool" value="$(arg publish_odom_tf)"/>
<param name="filters" type="str" value="$(arg filters)"/>
<param name="clip_distance" type="double" value="$(arg clip_distance)"/>
<param name="linear_accel_cov" type="double" value="$(arg linear_accel_cov)"/>
<param name="initial_reset" type="bool" value="$(arg initial_reset)"/>
<param name="unite_imu_method" type="str" value="$(arg unite_imu_method)"/>
<param name="allow_no_texture_points" type="bool" value="$(arg allow_no_texture_points)"/>
</node>
</launch>