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

[ROS2 Foxy][Gazebo] Can't make the libgazebo_ros_bumper plugin work

asked 2022-07-19 10:04:43 -0500

Bastian2909 gravatar image

Hello, I am using ros2 foxy and gazebo I am trying to integrate bumpers into my mobile robot but i can't find a way to make the libgazebo_ros_bumper plugin work in my urdf file

I first followed the logic of this link (https://github.com/ros-simulation/gaz...) but the topic bumper_demo wasn't even published. here is a part of my urdf file (the base_link link is defined earlier

<!-- front_bumper -->
  <link name="front_bumper">
    <collision>
      <geometry>
        <box size="0.03 0.400 0.03"/>
      </geometry>
    </collision>

    <visual>
      <geometry>
        <box size="0.03 0.400 0.03"/>
      </geometry>
      <material name="Cyan">
        <color rgba="0 1.0 1.0 1.0"/>
      </material>
    </visual>

    <xacro:box_inertia m="1" w="1.282" d="0.03" h="0.03"/>
  </link>

  <gazebo reference="front_bumper">
    <plugin name="bumper_plugin" filename="libgazebo_ros_bumper.so">
      <ros>
        <namespace>demo</namespace>
        <argument>bumper_states:=bumper_demo</argument>
      </ros>
      <frame_name>front_bumper</frame_name>
    </plugin>
  </gazebo>

  <joint name="front_bumper_joint" type="fixed">
    <parent link="base_link"/>
    <child link="front_bumper"/>
    <origin xyz="0.4812 0 -0.1514" rpy="0 0 0"/>
  </joint>
</robot>

Then I tried with what can be found on the gazebo official documentation : https://classic.gazebosim.org/tutoria...

  <gazebo>
    <plugin name="bumper_plugin" filename="libgazebo_ros_bumper.so">
      <alwaysOn>true</alwaysOn>
      <updateRate>20</updateRate>
      <bumperTopicName>front_bumper</bumperTopicName>
      <frameName>front_bumper</frameName>
    </plugin>
  </gazebo>

And the topic front_bumper still isn't published ... then I tried with the follwing code

  <gazebo reference="front_bumper">
    <plugin name="bumper_plugin" filename="libgazebo_ros_bumper.so">
      <alwaysOn>true</alwaysOn>
      <updateRate>20</updateRate>
      <bumperTopicName>front_bumper</bumperTopicName>
      <frameName>base_link</frameName>
    </plugin>
  </gazebo>

This code also doens't show anything new ...

I'm pretty lost right now so any advice would be greaty appreciated ! Thank you for taking the time to read this question.

edit retag flag offensive close merge delete

1 Answer

Sort by ยป oldest newest most voted
0

answered 2022-08-09 21:56:22 -0500

ChuiV gravatar image

The bumper plugin needs to be inside a <sensor> element in your urdf:

<gazebo reference="front_bumper">
    <sensor name=front_bumper_sensor" type="contact">
        <update_rate>10.0</update_rate>
        <contact>
            <!-- These collision names need to match the names used in the generated -->
            <!-- SDF, not the urdf names or this still won't work! -->
            <collision>front_bumper_collision</collision>
        </contact>
        <plugin name="bumper_plugin" filename="libgazebo_ros_bumper.so">
            <ros>
                <namespace>demo</namespace>
                <remapping>bumper_states:=bumper_demo</remapping>
            </ros>
        </plugin>
    </sensor>
</gazebo>

To find the actual collision name you should use in the collision element look at https://answers.ros.org/question/2771...

In summary, run gz sdf -p <your_filename>.urdf and check to see the collision name it generates for the front bumper collision, then put that name into the <collision> element.

You'll also need to give an actual name to the collision:

    <collision name="front_bumper_collision">
        <geometry>
            <box size="0.03 0.400 0.03"/>
        </geometry>
    </collision>
edit flag offensive delete link more

Question Tools

1 follower

Stats

Asked: 2022-07-19 10:04:43 -0500

Seen: 310 times

Last updated: Aug 09 '22