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>
SDF Spec
<collide_without_contact> Element Required: 0 Type: bool Default: false Description: Flag to disable contact force generation, while still allowing collision checks and contact visualization to occur.
tldr: collide_without_contact means the object will stop even though no "forces" are generated.