Gazebo | Ignition | Community
Ask Your Question
0

What is wrong with my Contact Sensor Code?

asked 2015-03-02 08:58:19 -0500

cyborg_x1 gravatar image

updated 2015-03-02 13:30:39 -0500

Hi,

For days I am trying to get my bumper working can you please tell me how to correct the following code?

I tried to get the answer on ros.answers already till I figured out yesterday that gazebo does not create the contact topic for the bumper and showes the following error:

* Internal Program Error - assertion (this->customContactPublishers.count(name) > 0) failed in std::string gazebo::physics::ContactManager::CreateFilter(const string&, const std::vector<std::basic_string<char> >&): /tmp/buildd/gazebo2-2.2.3/gazebo/physics/ContactManager.cc(329): Failed to create a custom filter Aborted (core dumped)

The question is WHY doesn't it create it and crashes instead. I tried multiple resources examples etc. I am also using the diff drive plugin, which creates contacts of the wheels properly.

The sensor itself is just a box, sitting in front of the robot on one side.

Here is the code in my xacro-URDF file.

<link name="bumper0">
<visual>
    <geometry>
        <box size="0.1 0.1 0.1" />
    </geometry>
</visual>
<collision name="bumper0_collision">
    <geometry>
        <box size="0.1 0.1 0.1" />
    </geometry>
</collision>
</link>
<joint name="chassis_bumper_joint" type="fixed">
<parent link="chassis" />
<child link="bumper0" />
<origin xyz="${chassis_len/2}  ${chassis_width/2} 0" rpy="0 0 0" />
<axis xyz="0 1 0"/> 
</joint>    

<gazebo reference="bumper0">
  <sensor name="bumper0_sensor" type="contact">
<always_on>true</always_on>
<update_rate>30</update_rate>
<contact>
  <collision>bumper0_collision</collision>
</contact>
<plugin name="bumper0_plugin" filename="libgazebo_ros_bumper.so">
  <bumperTopicName>bumper0_sensor_state</bumperTopicName>
  <frameName>bumper0</frameName>
</plugin>
</sensor>

</gazebo>

Through multiple posts I figured out that I need especially

<collision>bumper0_collision</collision>

to be either <link_name> + _collision or the name given in the name-attribute of the collision inside the link (SDF Tutorial)

<collision name="bumper0_collision">

Can anybody please help me out, and tell me what is wrong with my code?

The Gazebo Version is 2.2.3 on Kubuntu 14.04 (x64) on ROS indigo.

Thanks in advance.

edit retag flag offensive close merge delete

2 Answers

Sort by » oldest newest most voted
1

answered 2015-03-03 06:40:27 -0500

cyborg_x1 gravatar image

Thanks to ffurer, I found the problem now. I tried to have an empty base link for easier placement of the stuff. Well but actually the bumper seems to need full inertia setup in the chain from base link. Otherwise Gazebo crashes. Now I just need how to get a more "useful" topic from that contact, which can be got from a node on a real robot.

What I tried with my code above was:

CAUTION: CODE, NOT WORKING:

<link name="base_link"/><!-- PROBLEM -->
<link name="chassis">
 <xacro:inertia_box x="${chassis_len}" y="${chassis_width}" z="${chassis_height}" mass="1">
  <origin xyz="0  0 0" rpy="0 0 0" />
</xacro:inertia_box>
<visual>
    <geometry>
        <box size="${chassis_len} ${chassis_width} ${chassis_height}" />
    </geometry>
    <material name="Green">
        <color rgba="0 1 0 0.5"/>
    </material>
</visual>
<collision>
    <geometry>
        <box size="${chassis_len} ${chassis_width} ${chassis_height}" />
    </geometry>

</collision>
</link>


<gazebo reference="chassis">
<material value="Gazebo/Green"/>

</gazebo>


<joint name="base_chassis_joint" type="fixed">
<parent link="base_link" />
<child link="chassis" />
<origin xyz="0 0 ${chassis_floor_clearance+chassis_height/2}" rpy="0 0 0" />

</joint>
edit flag offensive delete link more
2

answered 2015-03-03 02:05:24 -0500

ffurrer gravatar image

I tried your example and made a complete robot with the information you provided:

<robot name="bumper_test" xmlns:xacro="http://ros.org/wiki/xacro">
  <xacro:macro name="box_inertial" params="x y z mass *origin">
    <inertial>
      <mass value="${mass}" />
      <xacro:insert_block name="origin" />
      <inertia ixx="${0.0833333 * mass * (y*y + z*z)}" ixy="0.0" ixz="0.0"
        iyy="${0.0833333 * mass * (x*x + z*z)}" iyz="0.0"
        izz="${0.0833333 * mass * (x*x + y*y)}" />
    </inertial>
  </xacro:macro>
  <link name="chassis">
    <xacro:box_inertial x="2" y="1" z="1" mass="100">
      <origin xyz="0  0 0" rpy="0 0 0" />
    </xacro:box_inertial>
    <visual>
      <geometry>
        <box size="2 1 1" />
      </geometry>
    </visual>
    <collision name="chassis_collision">
      <geometry>
        <box size="2 1 1" />
      </geometry>
    </collision>
  </link>
  <link name="bumper0">
    <visual>
      <geometry>
        <box size="0.1 0.1 0.1" />
      </geometry>
    </visual>
    <collision name="bumper0_collision">
      <geometry>
        <box size="0.1 0.1 0.1" />
      </geometry>
    </collision>
  </link>
  <joint name="chassis_bumper_joint" type="fixed">
    <parent link="chassis" />
    <child link="bumper0" />
    <origin xyz="1  0.5 0" rpy="0 0 0" />
    <axis xyz="0 1 0" />
  </joint>

  <gazebo reference="bumper0">
    <sensor name="bumper0_sensor" type="contact">
      <always_on>true</always_on>
      <update_rate>30</update_rate>
      <contact>
        <collision>bumper0_collision</collision>
      </contact>
      <plugin name="bumper0_plugin" filename="libgazebo_ros_bumper.so">
        <bumperTopicName>bumper0_sensor_state</bumperTopicName>
        <frameName>bumper0</frameName>
      </plugin>
    </sensor>
  </gazebo>
</robot>

which does work perfectly for me. Make sure you have the inertial properties set of your parent link.

Let me know if this example does work for you too. Cheers

edit flag offensive delete link more

Comments

Hmm, ok I see the code is working, ... so I guess the fault is somewhere else in my model code.

cyborg_x1 gravatar imagecyborg_x1 ( 2015-03-03 04:44:44 -0500 )edit

Thanks a lot for your help, I would give you a rate but currently I do not have enough Karma to do so ... do you know how I could get another topic from the node instead of the strange gazebo topic?

cyborg_x1 gravatar imagecyborg_x1 ( 2015-03-03 06:43:42 -0500 )edit

I'm not sure what you mean by another topic, from the node... if you just want to set a different topic you can do so by setting it `<bumpertopicname>` here. If you just want to check whether you are in collision you can do this somewhere else, where you subscribe to this topic or write your own plugin. Btw: you can always mark an answer as correct :)

ffurrer gravatar imageffurrer ( 2015-03-04 02:00:07 -0500 )edit

@ffurrer, did you try to change the maximum number of contacts?

nomad gravatar imagenomad ( 2015-04-14 08:00:48 -0500 )edit

There has to be inertia specified all the way down to the root element. `kdl_parser` may then complain about inertia on root element. While indigo's version of gazebo has issues with multiple bumper sensors anyway, seems updating ROS might be a good start.

Mr-Yellow gravatar imageMr-Yellow ( 2016-08-13 18:20:15 -0500 )edit


I've just tried this code in Gazebo 9 and /bumper0_sensor_state return empty states when bumper touches ground plane, below is an example of output:

header:
 seq: 399
 stamp:
  secs: 188
  nsecs: 66000000
 frame_id: "bumper0"
  states: []

Any ideas?

Tony gravatar imageTony ( 2019-10-10 00:42:15 -0500 )edit

Just figured out why it didn't work - I used xacro instead of urdf, detailed answer is here

Tony gravatar imageTony ( 2019-10-11 13:55:57 -0500 )edit

Question Tools

Stats

Asked: 2015-03-02 08:58:19 -0500

Seen: 2,599 times

Last updated: Mar 03 '15