ROS Resources: Documentation | Support | Discussion Forum | Index | Service Status | ros @ Robotics Stack Exchange
Ask Your Question
3

Getting contact sensor/bumper Gazebo plugin to work

asked 2016-10-25 22:19:38 -0500

RobB gravatar image

Has anyone had success with this? That is, creating a contact sensor/ bumper in urdf and connecting it to the Gazebo plugin described here ( http://gazebosim.org/tutorials?tut=ro... ), and then receiving the messages you'd expect on the defined topic.

My Gazebo code is:

<gazebo reference="bump_sensor">
<sensor name="main_bumper" type="contact">
    <selfCollide>true</selfCollide>
    <alwaysOn>true</alwaysOn>
    <updateRate>15.0</updateRate>
    <material>Gazebo/Red</material>
    <contact>
       <collision>bump_sensor_collision</collision>
    </contact>
    <plugin name="gazebo_ros_bumper_controller" filename="libgazebo_ros_bumper.so">   
        <bumperTopicName>bumper_vals</bumperTopicName>
        <frameName>world</frameName>
    </plugin>
</sensor>
</gazebo>

The model code is

<joint name="bumper_joint" type="fixed">
    <axis xyz="0 1 0" />
    <origin xyz=".2 0 0" rpy="0 0 0"/>
    <parent link="chassis"/>
    <child link="bump_sensor"/>   </joint>

 <link name="bump_sensor">
    <collision>
      <origin xyz="0 0 0" rpy="0 0 0"/>
      <geometry>
    <box size="0.1 0.1 0.1"/>
      </geometry>
    </collision>

    <visual>
      <origin xyz="0 0 0" rpy="0 0 0"/>
      <geometry>
         <box size="0.1 0.1 0.1"/>
      </geometry>
    </visual>

    <inertial>
      <mass value="1e-5" />
      <origin xyz="0 0 0" rpy="0 0 0"/>
      <inertia ixx="1e-6" ixy="0" ixz="0" iyy="1e-6" iyz="0" izz="1e-6" />
    </inertial>
  </link>

I don't think there is anything wrong with above. The topic bumper_vals is created and I can look at the messages to it via rostopic echo. They are in the expected gazebo_msgs/ContactState format. (or is it ContactsState?)

The point is that the states[] array is always empty even on an obvious collision.

Heaps of people seem to have had problems with bumpers (especially in simulation) and I don't see any clear cut answer. Why isn't there an effort to get this to work? If you know anything about robotics, then a contact sensor is the most basic thing you need to have working. Cameras, laser sensors re great, but the contact sensor is (should be) the simple, reliable backup that gets you out of trouble. And you can do a lot with it alone - e.g investigate and test path planning algorithms in spaces with obstacles, which is my project.

Any help greatly appreciated. Rob

edit retag flag offensive close merge delete

Comments

I'm having the exact same issue

neckutrek gravatar image neckutrek  ( 2016-12-13 06:57:14 -0500 )edit

2 Answers

Sort by ยป oldest newest most voted
5

answered 2017-02-27 07:02:54 -0500

updated 2017-02-27 07:03:22 -0500

You need apply the name attribute to your collision tag such as:

<collision name="bump_sensor_collision">
...
</collision>

This should make it work. However if specifying in urdf or xacro you may still have an issue in that the sensor doesn't output anything. In that case suffix the

<contact>
       <collision>bump_sensor_collision</collision>
</contact>

with a _collision, such that it reads:

<contact>
       <collision>bump_sensor_collision_collision</collision>
</contact>

This trick was due to how the sdf is generated from the urdf file, in that it was appending a _collision to the name attribute of the collision specification.

edit flag offensive delete link more

Comments

1

it can be more complicated that a simple _collision add but this is indeed the general idee ;) More details in the link in my answer ;)

TTDM gravatar image TTDM  ( 2017-03-01 02:44:06 -0500 )edit

This trick is very important. I spend a week on this. Really don't know why gazebo not give a demo directly.

littleghost gravatar image littleghost  ( 2018-06-27 03:06:50 -0500 )edit

I can not solve the problem, I also added the _collision, but it did not work, here is my xml in turtlebot3_burger.urdf.xacro

<gazebo reference="bump_sensor">
    <sensor name="main_bumper" type="contact">
        <selfCollide>true</selfCollide>
        <alwaysOn>true</alwaysOn>
        <updateRate>15.0</updateRate>
        <material>Gazebo/Red</material>
        <contact>
            <collision>bump_sensor_collision_collision</collision>
        </contact>
        <plugin name="gazebo_ros_bumper_controller" filename="libgazebo_ros_bumper.so">
            <bumperTopicName>bumper_vals</bumperTopicName>
            <frameName>world</frameName>
        </plugin>
    </sensor>
</gazebo>

here is my full bumper xml: https://ideone.com/Exwz1Z

HaiSanCamRanh gravatar image HaiSanCamRanh  ( 2020-02-18 03:06:39 -0500 )edit
1

This is why I didn't only say to add collision but to check the full explanation on my answer .... It has been later clarified for the simple case and this has become the accepted answer but the full explanation lie in my post in answer.gazebosim linked in my answer below.

TTDM gravatar image TTDM  ( 2020-02-18 09:29:25 -0500 )edit
1

@TTDM, thank you a lot, that is my mistake because of not checking your specific and wondrous answer. By checking the sdf with (gz sdf -p turtlebot3_burger.urdf.xacro), I found that your supplementary note is likely my problem. After seeing the collision name in the sdf file, I modified the turtlebot3_burger.urdf.xacro But the state output is still empty, I have checked by parse to sdf again and in the sdf file:

<collision name='base_footprint_fixed_joint_lump__bump_sensor_collision_collision_1'>
    <pose frame=''>0.05 0 0.03 0 -0 0</pose>
    ...
  </collision>

and the sensor tag,

<sensor name='main_bumper' type='contact'>
        <contact>
          <collision>base_footprint_fixed_joint_lump__bump_sensor_collision_collision_1</collision>
          <topic>__default_topic__</topic>
        </contact>
        ...

Did I miss or do anything wrong? here is my turtlebot3_burger.urdf.xacro: https://ideone.com/XGmhIQ Again, thank you a lot!

HaiSanCamRanh gravatar image HaiSanCamRanh  ( 2020-02-18 22:02:35 -0500 )edit

Hi, you forgot to declare "update rate" and "always on" on this last file. Also, in my code, i have them twice, once in the <gazebo> tag and once inside the <plugin> tag; even if i'm not sure its useful (but since i didn't tested it i still gives you the differences i see). Here is my code :

 <gazebo reference="${namespace}/base_link">
        <sensor name="collision_sensor" type="contact">
       <plugin name="gazebo_ros_bumper_controller" filename="libgazebo_ros_bumper.so"> 
<bumpertopicname>bumper_vals</bumpertopicname> <framename>world</framename> <alwayson>true</alwayson> <updaterate>1000.0</updaterate> </plugin> <always_on>true</always_on> <update_rate>1000.</update_rate> <contact> <collision>hummingbird/base_link_fixed_joint_lump__mav_collision_box_collision</collision> </contact> </sensor> </gazebo>

TTDM gravatar image TTDM  ( 2020-02-19 05:46:20 -0500 )edit
2

answered 2017-02-02 11:13:37 -0500

TTDM gravatar image

updated 2017-02-02 11:50:08 -0500

I solved a problem which was close to this one,( you can check here: http://answers.gazebosim.org/question... ) and I wonder if itsn't the same for you :

You call a "bump_sensor_collision" inside the gazebo flag to define the collision and you assume that it is created by the declaration of a collision inside the "bump_sensor" <link> ( which it should be ). However i found that the first name can be modified with a few supplementary informations so I invite you to check on the final sdf if your two names are identical and if they aren't to change the name inside the <gazebo> flag to make is match the collision in the <link>.

More information on how to do so are in the first link.

TTDM

edit flag offensive delete link more

Comments

Cheers. I'll give it a try. Rob

RobB gravatar image RobB  ( 2017-02-27 21:50:29 -0500 )edit

Question Tools

5 followers

Stats

Asked: 2016-10-25 22:19:38 -0500

Seen: 6,890 times

Last updated: Feb 27 '17