forked from SICKAG/sick_scan_xd
-
Notifications
You must be signed in to change notification settings - Fork 0
/
Copy pathsick_tim_7xx.launch
183 lines (171 loc) · 7.32 KB
/
sick_tim_7xx.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
<?xml version="1.0"?>
<!--
**********************************************
Launch File for TIM 7xx scanner
**********************************************
Start and stop angle is given in [rad]
Default min_angle is -135 degree.
Default max_angle is +135 degree.
Check IP-address, if your scanner is not found after roslaunch.
-->
<!-- You can launch a TIM_7xx-scanner on a specific ip address (e.g. 192.68.0.71) using the following example call:
roslaunch sick_scan sick_tim_7xx.launch hostname:=192.168.0.71
-->
<!-- Using node option required="true" will close roslaunch after node exits -->
<launch>
<arg name="nodename" default="sick_tim_7xx"/>
<arg name="hostname" default="192.168.0.1"/>
<arg name="port" default="2112"/>
<arg name="cloud_topic" default="cloud"/>
<arg name="frame_id" default="cloud"/>
<arg name="sw_pll_only_publish" default="true"/>
<arg name="add_transform_xyz_rpy" default="0,0,0,0,0,0"/>
<node name="$(arg nodename)" pkg="sick_scan" type="sick_generic_caller" respawn="false" output="screen" required="true">
<param name="scanner_type" type="string" value="sick_tim_7xx"/>
<param name="nodename" type="string" value="$(arg nodename)"/>
<param name="min_ang" type="double" value="-2.35619449"/> <!-- -135 deg -->
<param name="max_ang" type="double" value="2.35619449"/> <!-- +135 deg -->
<param name="use_binary_protocol" type="bool" value="True"/>
<param name="range_max" type="double" value="100.0"/>
<param name="intensity" type="bool" value="True"/>
<param name="hostname" type="string" value="$(arg hostname)"/>
<param name="cloud_topic" type="string" value="$(arg cloud_topic)"/>
<param name="frame_id" type="str" value="$(arg frame_id)"/>
<param name="port" type="string" value="$(arg port)"/>
<param name="timelimit" type="int" value="5"/>
<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="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="min_intensity" type="double" value="0.0"/> <!-- Set range of LaserScan messages to infinity, if intensity < min_intensity (default: 0) -->
<!-- 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="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 -->
<param name="client_authorization_pw" type="string" value="F4724744"/> <!-- Default password for client authorization -->
</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
-->