GPU laser sensor reflects transparent glass material
Hello, I want to simulate a glass wall in Gazebo and see that the laser scanner can't detect it. In my model I tried to give different laser_retro and transparency settings. In Rviz I always see that the transparent wall reflects the laser scans. Can anybody shed some light on this ?
EDIT
I use Gazebo version 7.4 ROS Kinetic on Ubuntu 16.04
Below is the wall that is supposed not to reflect laser scans.
<model name="glass1">
<static>true</static>
<pose>7 2 1 0 0 0</pose>
<link name="link">
<collision name="visual">
<laser_retro>0.5</laser_retro>
<geometry><box><size>0.1 2 2</size></box></geometry>
</collision>
<visual name="visual1">
<transparency>1</transparency>
<geometry><box><size>0.1 2 2</size></box></geometry>
<material>
<script><name>Gazebo/RedTransparent</name></script>
</material>
</visual>
</link>
</model>
Here is the laser plugin definition:
<gazebo reference="hokuyo_link">
<material>Gazebo/Red</material>
<sensor type="gpu_ray" name="hokuyo">
<pose>0 0 0 0 0 0</pose>
<visualize>false</visualize>
<update_rate>40</update_rate>
<ray>
<scan>
<horizontal>
<samples>720</samples>
<resolution>1</resolution>
<min_angle>-1.570796</min_angle>
<max_angle>1.570796</max_angle>
</horizontal>
</scan>
<range>
<min>0.10</min> <max>30.0</max>
<resolution>0.01</resolution>
</range>
</ray>
<plugin name="gpu_laser" filename="libgazebo_ros_gpu_laser.so">
<topicName>/scan</topicName>
<frameName>hokuyo_link</frameName>
</plugin>
</sensor>
</gazebo>
Asked by bustun on 2017-01-26 07:16:16 UTC
Answers
So basically the gpu laser will only detect a link's visual. One solution to your problem would be to simply delete the
<visual name="visual1">
...
</visual>
in your sdf. But you would not be able to see the object in the simulation. Another possibility is to delete the
<collision name="visual">
...
</collision>
Element in your sdf and use the non gpu version of the sensor. This sensor will only detect a link's collision and you will be still able to see the object in the simulation. To do this you also need to change the sensor type:
<sensor type="ray" name="hokuyo">
and the plugin:
<plugin name="gazebo_ros_head_hokuyo_controller" filename="libgazebo_ros_laser.so">
Asked by wentz on 2018-09-06 09:46:38 UTC
Comments
Can you post the version of gazebo you are using, the models you are simulating, the version of ROS, and any relevant code?
Asked by nkoenig on 2017-01-26 10:37:36 UTC