Gazebo Fortress Contact Sensor disable collision
Hey I would like to create a contact sensor which will detect collisions with it, but not actually collide or interfere with any moving objects. Just send information that it has been collided with.
Currently have the following code for it, but the model seems to stop when it hits this object.
<model name="wheel_sensor">
<static>true</static>
<pose>0.4 -4 6.9 0 0 0</pose>
<link name="wheel_entry_sensor">
<pose/>
<inertial>
<mass>1.14395</mass>
<inertia>
<ixx>9.532917</ixx>
<ixy>0</ixy>
<ixz>0</ixz>
<iyy>0.023832</iyy>
<iyz>0</iyz>
<izz>9.556749</izz>
</inertia>
</inertial>
<visual name="visual">
<geometry>
<box>
<size>0.2 0.2 0.9</size>
</box>
</geometry>
</visual>
<collision name="collision">
<geometry>
<box>
<size>0.2 0.2 0.9</size>
</box>
</geometry>
<surface>
<contact>
<collide_without_contact>true</collide_without_contact>
</contact>
</surface>
</collision>
<sensor name='entry_sensor' type='contact'>
<contact>
<topic>wheel_entry</topic>
<collision>collision</collision>
</contact>
</sensor>
</link>
</model>
Asked by Hokul on 2023-01-11 23:36:16 UTC
Answers
To the best of my knowledge, this is unavoidable. The collision is detected and has an impact on the physics of the simulation.
The best way for your collision to have little impact is to remove the object you collided with from the simulation programmatically but I believe that's not what you want to achieve. See: https://community.gazebosim.org/t/reinforcement-learning-using-gazebo/1607/3?u=alex_ssom for detail on how to do that.
Asked by alex-ssom on 2023-01-12 14:02:29 UTC
Comments
Cheers for the quick response, that was very helpful. I'll be able to try some different solution now :).
Asked by Hokul on 2023-01-12 17:23:28 UTC
If it fits your simulation, you could consider attaching the contact sensor to an essentially flat collision element just above the ground plane. I use boxes with x,y,0.001 size and they work fine. Of course this would only work in cases when you want to detect "driving over" a specific area.
edit: I use Gazebo-11, so YMMV
Asked by Gavriel-CTO on 2023-01-29 03:00:50 UTC
Comments
SDF Spec
tldr: collide_without_contact means the object will stop even though no "forces" are generated.
Asked by Gavriel-CTO on 2023-01-30 04:54:51 UTC