/
helios-32-FOV-70.sensor.xml
40 lines (31 loc) · 2.31 KB
/
helios-32-FOV-70.sensor.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
<sensor class="lidar3d" name="${sensor_name|lidar1}">
<pose_3d> ${sensor_x|0.5} ${sensor_y|0.0} ${sensor_z|0.7} ${sensor_yaw|0.0} ${sensor_pitch|0.0} ${sensor_roll|0.0}</pose_3d>
<!-- vert_fov_degrees: If defined, a symmetric vertical FOV is used.
The alternative is using a custom list of angles in "vertical_ray_angles"
-->
<!-- <vert_fov_degrees>${vert_fov_degrees|70}</vert_fov_degrees> -->
<vert_nrays>32</vert_nrays>
<vertical_ray_angles>-55.020 -52.081 -49.142 -46.204 -43.265 -40.326 -37.387 -34.449 -31.510 -28.571 -25.632 -22.694 -19.755 -16.816 -13.877 -10.939 -8.000 -6.667 -5.333 -4.000 -2.667 -1.333 0.000 1.333 2.667 4.000 5.333 6.667 8.754 10.841 12.929 15</vertical_ray_angles>
<!-- Horizontal / azimuth angular resolution:
The rotation of the Helios sensor configurable: 5 / 10 / 20 Hz
Firing timing of the sensor is fixed at 55.296 μs (=18.084 kHz).
Set the "sensor_rate" (Hz) variable from the parent XML to automatically
adjust the number of points per horizontal line.
-->
<sensor_period>$f{1.0/${sensor_rate|10}}</sensor_period>
<horz_nrays>$f{(1.0/${sensor_rate|10})/55.296e-6}</horz_nrays>
<!-- 1.0=minimum (faster), larger values=potentially finer details captured -->
<horz_resolution_factor>${horz_resolution_factor|1.0}</horz_resolution_factor>
<vert_resolution_factor>${vert_resolution_factor|1.0}</vert_resolution_factor>
<!-- Depth ratio (0 to 1) between adjacent depth image to allow linear interpolation of ranges -->
<max_vert_relative_depth_to_interpolatate>${max_vert_relative_depth_to_interpolatate|0.3}</max_vert_relative_depth_to_interpolatate>
<max_horz_relative_depth_to_interpolatate>${max_horz_relative_depth_to_interpolatate|0.1}</max_horz_relative_depth_to_interpolatate>
<range_std_noise>${sensor_std_noise|0.005}</range_std_noise>
<min_range>${min_range|0.20}</min_range>
<max_range>${max_range|110.0}</max_range>
<visual> <model_uri>${MVSIM_CURRENT_FILE_DIRECTORY}/../models/velodyne-vlp16.dae</model_uri> <model_roll>90</model_roll> </visual>
<!-- Publish sensor on MVSIM ZMQ topic? (Note, this is **not** related to ROS at all) -->
<publish enabled="${sensor_publish|false}">
<publish_topic>/${PARENT_NAME}/${NAME}</publish_topic>
</publish>
</sensor>