-
Notifications
You must be signed in to change notification settings - Fork 87
/
sick_lms_5xx.launch
254 lines (240 loc) · 14.7 KB
/
sick_lms_5xx.launch
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
182
183
184
185
186
187
188
189
190
191
192
193
194
195
196
197
198
199
200
201
202
203
204
205
206
207
208
209
210
211
212
213
214
215
216
217
218
219
220
221
222
223
224
225
226
227
228
229
230
231
232
233
234
235
236
237
238
239
240
241
242
243
244
245
246
247
248
249
250
251
252
253
<?xml version="1.0"?>
<!--
*****************************************************************************
* Launch Example File for SICK LMS 511 *
*****************************************************************************
-->
<!-- start and stop angle is given in [rad] -->
<!--
Check IP-address, if you scanner is not found after roslaunch.
-->
<!-- Using node option required="true" will close roslaunch after node exits -->
<launch>
<arg name="hostname" default="192.168.0.1"/>
<arg name="cloud_topic" default="cloud"/>
<arg name="laserscan_topic" default="scan"/>
<arg name="frame_id" default="cloud"/>
<arg name="sw_pll_only_publish" default="true"/>
<arg name="nodename" default="sick_lms_5xx"/>
<arg name="add_transform_xyz_rpy" default="0,0,0,0,0,0"/>
<arg name="add_transform_check_dynamic_updates" default="false"/> <!-- Note: dynamical updates of parameter add_transform_xyz_rpy can decrease the performance and is therefor deactivated by default -->
<arg name="encoder_mode" default="-1"/> <!-- Encoder settings (default: -1, i.e. not set): 0: Off, 1: Single increment, 2: Direction recognition phase, 3: Direction recognition level, 4: Fixed increment speed/ticks (LMS4000 only) -->
<!-- launch file for the lms_5xx series -->
<arg name="tf_publish_rate" default="10.0" /> <!-- Rate to publish TF messages in hz, use 0 to deactivate TF messages -->
<node name="$(arg nodename)" pkg="sick_scan_xd" type="sick_generic_caller" respawn="false" output="screen" required="true">
<!-- launch-prefix="gdb -ex run - -args" -->
<!-- default values: -->
<!--
<param name="min_ang" type="double" value="-1.658062789" />
<param name="max_ang" type="double" value="1.658062789" />
<param name="intensity" type="bool" value="True" />
<param name="skip" type="int" value="0" />
<param name="time_offset" type="double" value="-0.001" />
<param name="publish_datagram" type="bool" value="False" />
<param name="subscribe_datagram" type="bool" value="false" />
<param name="device_number" type="int" value="0" />
<param name="range_min" type="double" value="0.05" />
-->
<param name="min_ang" type="double" value="-1.658062789" />
<param name="max_ang" type="double" value="1.658062789" />
<param name="cloud_topic" type="string" value="$(arg cloud_topic)"/>
<param name="laserscan_topic" type="string" value="$(arg laserscan_topic)"/>
<param name="frame_id" type="str" value="$(arg frame_id)"/>
<param name="scanner_type" type="string" value="sick_lms_5xx"/>
<!-- Optional range filter configuration: If the range of a scan point is less than range_min or greater than range_max, the point can be filtered. -->
<!-- Depending on parameter range_filter_handling, the following filter can be applied for points with a range not within [range_min, range_max], -->
<!-- see enumeration RangeFilterResultHandling in range_filter.h: -->
<!-- 0: RANGE_FILTER_DEACTIVATED, do not apply range filter (default) -->
<!-- 1: RANGE_FILTER_DROP, drop point, if range is not within [range_min, range_max] -->
<!-- 2: RANGE_FILTER_TO_ZERO, set range to 0, if range is not within [range_min, range_max] -->
<!-- 3: RANGE_FILTER_TO_RANGE_MAX, set range to range_max, if range is not within [range_min, range_max] -->
<!-- 4: RANGE_FILTER_TO_FLT_MAX, set range to FLT_MAX, if range is not within [range_min, range_max] -->
<!-- 5: RANGE_FILTER_TO_NAN set range to NAN, if range is not within [range_min, range_max] -->
<!-- Note: Range filter applies only to Pointcloud messages, not to LaserScan messages. -->
<!-- Using range_filter_handling 4 or 5 requires handling of FLT_MAX and NAN values in an application. -->
<param name="range_min" type="double" value="0.05"/>
<param name="range_max" type="double" value="100.0"/>
<param name="range_filter_handling" type="int" value="0"/>
<param name="intensity" type="bool" value="true"/>
<param name="intensity_resolution_16bit" type="bool" value="false"/>
<param name="hostname" type="string" value="$(arg hostname)"/>
<param name="port" type="string" value="2112"/>
<param name="timelimit" type="int" value="5"/>
<param name="use_binary_protocol" type="bool" value="true"/>
<param name="filter_echos" type="int" value="2"/> <!-- FREchoFilter settings: 0: first echo, 1: all echos, 2: last echo -->
<param name="sw_pll_only_publish" type="bool" value="$(arg sw_pll_only_publish)"/>
<param name="use_generation_timestamp" type="bool" value="true"/> <!-- Use the lidar generation timestamp (true, default) or send timestamp (false) for the software pll converted message timestamp -->
<param name="min_intensity" type="double" value="0.0"/> <!-- Set range of LaserScan messages to infinity, if intensity < min_intensity (default: 0) -->
<param name="encoder_mode" type="int" value="$(arg encoder_mode)"/> <!-- Encoder settings (default: -1, i.e. not set): 0: Off, 1: Single increment, 2: Direction recognition phase, 3: Direction recognition level, 4: Fixed increment speed/ticks (LMS4000 only) -->
<param name="scandatacfg_timingflag" type="int" value="-1"/> <!-- Set timing flag LMDscandatacfg (LMS-1XX, LMS-1XXX, LMS-4XXX, LMS-5XX, MRS-1XXX, MRS-6XXX, NAV-2XX, TIM-240, TIM-4XX, TIM-5XX, TIM-7XX, TIM-7XXS): -1: use default (off for TiM-240, otherwise on), 0: do not send time information, 1: send time information -->
<!-- possible angular resolutions are 1,0.6667,0.5,0.3333,0.25,0.1667
possible scan frequencies are 25,35,50,75,100 Hz
Make sure to check in the manual whether the desired scanning frequency
and angular resolution combination is available.
The parameters scan_freq and ang_res must always be used together.
<param name="ang_res" type="double" value="0.1667" />
<param name="scan_freq" type="double" value="25" />
-->
<!-- Apply an additional transform to the cartesian pointcloud, default: "0,0,0,0,0,0" (i.e. no transform) -->
<!-- Note: add_transform_xyz_rpy is specified by 6D pose x, y, z, roll, pitch, yaw in [m] resp. [rad] -->
<!-- It transforms a 3D point in cloud coordinates to 3D point in user defined world coordinates: -->
<!-- add_transform_xyz_rpy := T[world,cloud] with parent "world" and child "cloud", i.e. P_world = T[world,cloud] * P_cloud -->
<!-- The additional transform applies to cartesian lidar pointclouds and visualization marker (fields) -->
<!-- It is NOT applied to polar pointclouds, radarscans, ldmrs objects or other messages -->
<param name="add_transform_xyz_rpy" type="string" value="$(arg add_transform_xyz_rpy)" />
<param name="add_transform_check_dynamic_updates" type="bool" value="$(arg add_transform_check_dynamic_updates)" />
<param name="start_services" type="bool" value="True"/> <!-- start ros service for cola commands -->
<param name="activate_lferec" type="bool" value="True"/> <!-- activate field monitoring by lferec messages -->
<param name="activate_lidoutputstate" type="bool" value="True"/> <!-- activate field monitoring by lidoutputstate messages -->
<param name="activate_lidinputstate" type="bool" value="True"/> <!-- activate field monitoring by lidinputstate messages -->
<param name="message_monitoring_enabled" type="bool" value="True" /> <!-- Enable message monitoring with reconnect+reinit in case of timeouts, default: true -->
<param name="read_timeout_millisec_default" type="int" value="5000"/> <!-- 5 sec read timeout in operational mode (measurement mode), default: 5000 milliseconds -->
<param name="read_timeout_millisec_startup" type="int" value="120000"/> <!-- 120 sec read timeout during startup (sensor may be starting up, which can take up to 120 sec.), default: 120000 milliseconds -->
<param name="read_timeout_millisec_kill_node" type="int" value="150000"/> <!-- 150 sec pointcloud timeout, ros node will be killed if no point cloud published within the last 150 sec., default: 150000 milliseconds -->
<!-- Note: read_timeout_millisec_kill_node less or equal 0 deactivates pointcloud monitoring (not recommended) -->
<param name="client_authorization_pw" type="string" value="F4724744"/> <!-- Default password for client authorization -->
<!-- Configuration of ROS quality of service: -->
<!-- On ROS-1, parameter "ros_qos" sets the queue_size of ros publisher -->
<!-- On ROS-2, parameter "ros_qos" sets the QoS of ros publisher to one of the following predefined values: -->
<!-- 0: rclcpp::SystemDefaultsQoS(), 1: rclcpp::ParameterEventsQoS(), 2: rclcpp::ServicesQoS(), 3: rclcpp::ParametersQoS(), 4: rclcpp::SensorDataQoS() -->
<!-- See e.g. https://docs.ros2.org/dashing/api/rclcpp/classrclcpp_1_1QoS.html#ad7e932d8e2f636c80eff674546ec3963 for further details about ROS2 QoS -->
<!-- Default value is -1, i.e. queue_size=10 on ROS-1 resp. qos=rclcpp::SystemDefaultsQoS() on ROS-2 is used.-->
<param name="ros_qos" type="int" value="-1"/> <!-- Default QoS=-1, i.e. do not overwrite, use queue_size=10 on ROS-1 resp. qos=rclcpp::SystemDefaultsQoS() on ROS-2 -->
<!--
On ROS-1 and ROS-2, sick_scan_xd publishes TF messsages to map a given base frame (i.e. base coordinates system) to the lidar frame (i.e. lidar coordinates system) and vice versa.
The default base frame id is "map" (which is the default frame in rviz).
The default 6D pose is (x,y,z,roll,pitch,yaw) = (0,0,0,0,0,0) defined by position (x,y,z) in meter and (roll,pitch,yaw) in radians.
This 6D pose (x,y,z,roll,pitch,yaw) is the transform T[base,lidar] with parent "base" and child "lidar".
For lidars mounted on a carrier, the lidar pose T[base,lidar] and base frame can be configured in this launchfile using the following parameter.
The lidar frame id given by parameter "frame_id" resp. "publish_frame_id".
Note that the transform is specified using (x,y,z,roll,pitch,yaw). In contrast, the ROS static_transform_publisher uses commandline arguments in order (x,y,z,yaw,pitch,roll).
-->
<param name="tf_base_frame_id" type="string" value="map" /> <!-- Frame id of base coordinates system, e.g. "map" (default frame in rviz) -->
<param name="tf_base_lidar_xyz_rpy" type="string" value="0,0,0,0,0,0" /> <!-- T[base,lidar], 6D pose (x,y,z,roll,pitch,yaw) in meter resp. radians with parent "map" and child "cloud" -->
<param name="tf_publish_rate" type="double" value="$(arg tf_publish_rate)" /> <!-- Rate to publish TF messages in hz, use 0 to deactivate TF messages -->
<!--
Optional mode to convert lidar ticks to ros- resp. system-timestamps:
tick_to_timestamp_mode = 0 (default): convert lidar ticks in microseconds to system timestamp by software-pll
tick_to_timestamp_mode = 1 (optional tick-mode): convert lidar ticks in microseconds to timestamp by 1.0e-6*(curtick-firstTick)+firstSystemTimestamp
tick_to_timestamp_mode = 2 (optional tick-mode): convert lidar ticks in microseconds directly into a lidar timestamp by sec = tick/1000000, nsec = 1000*(tick%1000000)
Note: Using tick_to_timestamp_mode = 2, the timestamps in ROS message headers will be in lidar time, not in system time. Lidar and system time can be very different.
Using tick_to_timestamp_mode = 2 might cause unexpected results or error messages. We recommend using tick_to_timestamp_mode = 2 for special test cases only.
-->
<param name="tick_to_timestamp_mode" type="int" value="0"/>
</node>
</launch>
<!--
Conversion between degree and rad
DEG RAD
-180 -3.141592654
-175 -3.054326191
-170 -2.967059728
-165 -2.879793266
-160 -2.792526803
-155 -2.705260341
-150 -2.617993878
-145 -2.530727415
-140 -2.443460953
-137.5 -2,3998277
-135 -2.35619449
-130 -2.268928028
-125 -2.181661565
-120 -2.094395102
-115 -2.00712864
-110 -1.919862177
-105 -1.832595715
-100 -1.745329252
-95 -1.658062789
-90 -1.570796327
-85 -1.483529864
-80 -1.396263402
-75 -1.308996939
-70 -1.221730476
-65 -1.134464014
-60 -1.047197551
-55 -0.959931089
-50 -0.872664626
-45 -0.785398163
-40 -0.698131701
-35 -0.610865238
-30 -0.523598776
-25 -0.436332313
-20 -0.34906585
-15 -0.261799388
-10 -0.174532925
-5 -0.087266463
0 0
5 0.087266463
10 0.174532925
15 0.261799388
20 0.34906585
25 0.436332313
30 0.523598776
35 0.610865238
40 0.698131701
45 0.785398163
50 0.872664626
55 0.959931089
60 1.047197551
65 1.134464014
70 1.221730476
75 1.308996939
80 1.396263402
85 1.483529864
90 1.570796327
95 1.658062789
100 1.745329252
105 1.832595715
110 1.919862177
115 2.00712864
120 2.094395102
125 2.181661565
130 2.268928028
135 2.35619449
137.5 2,3998277
140 2.443460953
145 2.530727415
150 2.617993878
155 2.705260341
160 2.792526803
165 2.879793266
170 2.967059728
175 3.054326191
180 3.141592654
185 3.228859116
190 3.316125579
195 3.403392041
200 3.490658504
205 3.577924967
210 3.665191429
215 3.752457892
220 3.839724354
225 3.926990817
230 4.01425728
235 4.101523742
240 4.188790205
245 4.276056667
250 4.36332313
255 4.450589593
260 4.537856055
265 4.625122518
270 4.71238898
275 4.799655443
280 4.886921906
285 4.974188368
290 5.061454831
295 5.148721293
300 5.235987756
305 5.323254219
310 5.410520681
315 5.497787144
320 5.585053606
325 5.672320069
330 5.759586532
335 5.846852994
340 5.934119457
345 6.021385919
350 6.108652382
355 6.195918845
360 6.283185307
-->