Is it possible to have one of the lidar sensors from here: http://sdformat.org/spec?ver=1.9&elem=sensor#link_sensor (preferably the gpu_lidar) interact selectively with objects in a Gazebo scene? i.e. I'd like a LIDAR sensor to be able to only interact with objects/models of my choosing vs all in a scene.
If so, what are the option for doing so? My internet search thus far has turned up mostly empty with a possible hint here: https://answers.gazebosim.org/question/25156/how-to-make-ray-sensor-ignore-body-of-the-robot/.
It turns out after digging through https://github.com/gazebosim and its various repositories corresponding to the lidar sensor, that the visibility_mask
element applies to the sensor type "gpu_lidar" as well as sensor type "camera" (the only sensor it is currently mentioned for on the SDF webpage) and will work for models in the world/sdf that have a visual element with its visibility_tag
set accordingly. This works on ros2 galactic.
So something like the following sensor definition in a urdf file will not see the SDF model defined below:
<gazebo reference="tool">
<sensor type="gpu_lidar" name="gpu_lidar">
<update_rate>40.0</update_rate>
<always_on>1</always_on>
<topic>sonar</topic>
<visualize>1</visualize>
<ignition_frame_id>left_tool</ignition_frame_id>
<ray>
<scan>
<horizontal>
<samples>15</samples>
<resolution>1.0</resolution>
<min_angle>-0.1309</min_angle>
<max_angle>0.1309</max_angle>
</horizontal>
<vertical>
<samples>15</samples>
<resolution>1.0</resolution>
<min_angle>-0.1309</min_angle>
<max_angle>0.1309</max_angle>
</vertical>
</scan>
<range>
<min>0.02</min>
<max>4.0</max>
</range>
<visibility_mask>4294967294</visibility_mask>
</ray>
<plugin filename="ignition-gazebo-sensors-system" name="ignition::gazebo::systems::Sensors">
</plugin>
</sensor>
</gazebo>
Model SDF:
<model name='tower'>
<pose>0.066472 2.94969 0.5 0 -0 0</pose>
<link name='cylinder_link'>
<inertial>
<inertia>
<ixx>0.14580000000000001</ixx>
<ixy>0</ixy>
<ixz>0</ixz>
<iyy>0.14580000000000001</iyy>
<iyz>0</iyz>
<izz>0.125</izz>
</inertia>
<mass>1</mass>
<pose>0 0 0 0 -0 0</pose>
</inertial>
<collision name='cylinder_collision'>
<geometry>
<cylinder>
<radius>0.5</radius>
<length>1</length>
</cylinder>
</geometry>
<surface>
<friction>
<ode/>
</friction>
<bounce/>
<contact/>
</surface>
</collision>
<visual name='cylinder_visual'>
<visibility_flags>1</visibility_flags>
<geometry>
<cylinder>
<radius>0.5</radius>
<length>1</length>
</cylinder>
</geometry>
<material>
<ambient>0.3 0.3 0.3 1</ambient>
<diffuse>0.7 0.7 0.7 1</diffuse>
<specular>1 1 1 1</specular>
</material>
</visual>
<pose>0 0 0 0 -0 0</pose>
<enable_wind>false</enable_wind>
</link>
<static>false</static>
<self_collide>false</self_collide>
</model>