No impact of laser_retro when using ray sensor.
I feel like I don't understand the laser_retro
parameter of a collision object (http://sdformat.org/spec?ver=1.6&elem...).
I don't see any impact of changing the laser_retro
parameter. The scan output is the same and also the visualization looks the same to me (when checking the parameter in gazebo GUI, it is set correctly). What exactly is the use of this parameter? I was hoping, that I could decide wheter a collision reflects a ray of a laser scan or not (to make some collisions invisible for the sensor).
I created the following sdf to play around with the laser_retro
using ray
and gpu_ray
sensor.
<?xml version="1.0" ?>
<sdf version="1.6">
<world name="my_world">
<model name="sensor">
<link name="sensor_link">
<gravity>0</gravity>
<pose>0 0 0.1 </pose>
<visual name="sensor_visual">
<geometry>
<box>
<size>0.05 0.05 0.05</size>
</box>
</geometry>
</visual>
<sensor type="gpu_ray" name="my_sensor">
<visualize>1</visualize>
<ray>
<scan>
<horizontal>
<resolution>1</resolution>
<min_angle>0</min_angle>
<max_angle>3</max_angle>
</horizontal>
</scan>
<range>
<min>0.10</min>
<max>5.0</max>
</range>
</ray>
</sensor>
</link>
</model>
<model name="obstacle_box">
<link name="obstacle_link">
<gravity>0</gravity>
<pose> 2 2 0.1 </pose>
<visual name="obstacle_visual">
<geometry>
<box>
<size>0.5 0.5 0.5</size>
</box>
</geometry>
</visual>
<collision name="obstacle_collision">
<geometry>
<box>
<size>0.2 0.2 0.2</size>
</box>
</geometry>
<laser_retro>0</laser_retro>
</collision>
</link>
</model>
</world>
</sdf>
Using gazebo 9.13 Thanks!
EDIT:
After checking the gz topic output of my sensor I can see that the intensity value is returned correctly. But the range of the rays colliding with the model is still being published. So I guess, the laser_retro
value is only for intensity.
NOW: Is there a way to make the collision completely invisible for a ray
sensor, so there is not range published ? (I can't use gpu_ray
).