Robotics StackExchange | Archived questions

Contact sensor generates no contact information using gazebo_ros_bumper plugin

Hi everyone,

I am trying to get the gazebo_ros_bumper plugin to work.

All information I can see are the rising time steps, when I am listening to the topic via rostopic. The states array stays empty.

I used a predifined robot from the gazebo database as an obstacle to avoid colliding with a model in "resting state" like in the attached picture. But this doesn't seem to work either.

image description

This is how I implement the plugin in my SDF model.

<link name="bumper_base">
    <pose>-0.075 0 0.05   0 0 0</pose>
    <inertial>
        <mass>0.01</mass>
    </inertial>
    <collision name="bumper_base_collision">
        <pose>0.0 0 0   0 0 0</pose>
        <geometry>
            <cylinder>
                <radius>0.33</radius>
                <length>0.03</length>
            </cylinder>
        </geometry>
    </collision>
    <visual name="bumper_base_visual">
        <pose>0 0 0   0 0 0</pose>
        <geometry>
            <cylinder>
                <radius>0.33</radius>
                <length>0.03</length>
            </cylinder>
        </geometry>
        <material>
            <ambient>0.83 0.55 0.09 1</ambient>         
        </material> 
    </visual>

   <collision name="bumper_tail_collision">
        <pose>-0.30 0 0   0 0 0</pose>
        <geometry>
            <cylinder>
                <radius>0.18</radius>
                <length>0.03</length>
            </cylinder>
        </geometry>
    </collision>
    <visual name="bumper_tail_visual">
        <pose>-0.30 0 0   0 0 0</pose> 
        <geometry>
            <cylinder>
                <radius>0.18</radius>
                <length>0.03</length>
            </cylinder>
        </geometry>
        <material>
            <ambient>0.83 0.55 0.09 1</ambient>
        </material>
    </visual>


    <sensor name="bumper_front" type="contact">
        <always_on>true</always_on>
        <update_rate>10</update_rate>
        <visualize>true</visualize>
        <pose>0 0 0   0 0 0</pose>
        <topic>bumper_base</topic>
        <contact>
            <collision>bumper_base_collision></collision>
            <topic>bumper_base</topic>
        </contact>

        <plugin name="gazebo_ros_laser" filename="/home/christoph/catkin_workspace_groovy/devel/lib/libgazebo_ros_bumper.so">
            <bumperTopicName>bumper_base</bumperTopicName> 
            <frameName>bumper_base</frameName>
        </plugin> 
    </sensor>
</link>



<!-- Bumper Joint -->
<joint name="bumper_front_joint" type="revolute">
    <pose>0  0  0  0  0  0</pose>
    <parent>base_link</parent>
    <child>bumper_base</child>
    <axis>
        <xyz>1 0 0</xyz>
        <limit>
            <upper>0</upper>
            <lower>0</lower>
        </limit>
    </axis>
</joint>

My plan is to check the size of the state array from the contact message to see if there are any collisions.

Is it correct, that the callback function will recieve messages in the given update_rate even if there aren't any collisions? And is this necessary or is it possible to only get messages when a collision is detected?

Update 1:

I tried to get a collision reaction by building a collision obstacle like in this tutorial: link

But that didn't change anything.

Thanks in advance, Christoph

Asked by Christoph on 2013-11-28 17:44:28 UTC

Comments

Answers

First of all, you can check there is really collision or not through gztopic echo "~~~".

In the topic list, there might be some "physics/contacts" exists. If you echo that, you can see whether "bumper_base_collision" element really generate collision or not. After that, you can also check other "contacts" topic and the sensor topics.

PS. your sensor refers "bumper_base_collision>". Probably, I think ">" is typo.

Asked by Daehyung Park on 2014-01-07 14:48:22 UTC

Comments

It seems you were showing the SDF file instead of URDF....sorry, my mistake... Anyway, have you solved the problem, anything you could share on this question? Thanks!

Asked by shawnysh on 2017-06-11 22:57:15 UTC

sensor tag should be put in gazebo tag, since these plugin information belongs to gazebo-specific used inSDF file instead of URDF Here is the reference link

Though it turns out that problem remains the same, the answer below that question indicates a parse problem that cause non-message.

But I haven't fixed it, hope this hint could help you through!

Asked by shawnysh on 2017-06-11 22:54:57 UTC

Comments