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

How do I use force sensor & bumper sensor in Gazebo?

asked 2012-03-05 14:38:32 -0500

kichistays gravatar image

updated 2021-09-27 08:59:00 -0500

lucasw gravatar image

I am designing a biped robot model in gazebo. I am trying to add force sensors on the bottom of the foot, but I don't know what parameters I need to do that.. so far this is what I have written in my urdf.xacro file. If I correct if the sensor got implemented then it should publish the sensor data, right?? .Please let me know if I am missing something or have written it wrong.

<link name="R_leg">
  <inertial>
    <origin xyz="0 0.0 -0.124" rpy="0 0 0 "/>
    <mass value="0.15" />
    <inertia  ixx="1.0" ixy="0.0"  ixz="0.0"  iyy="1.0"  iyz="0.0" izz="1.0" />
  </inertial>
  <visual>
    <origin xyz="0 0.0 -0.124" rpy="0 0 0 "/>
    <geometry>
      <box size="0.1 0.12 0.25" />
    </geometry>
  </visual>
  <collision>
    <origin xyz="0 0.0 -0.124" rpy="0 0 0 "/>
    <geometry>
      <box size="0.1 0.12 0.20" />
    </geometry>
  </collision>
</link>
<gazebo reference="R_leg">
  <material>Gazebo/White</material>
  <turnGravityOff>false</turnGravityOff>
</gazebo>

<link name="R_foot">
  <inertial>
    <origin xyz="0 0.0 -0.010"  rpy="0 0 0"/>
    <mass value="0.15" />
    <inertia  ixx="1.0" ixy="0.0"  ixz="0.0"  iyy="1.0"  iyz="0.0" izz="1.0" />
  </inertial>
  <visual>
    <origin xyz="0 0.0 -0.010"  rpy="0 0 0"/>
    <geometry>
      <box size="0.2 0.12 0.02" />
    </geometry>
  </visual>
  <collision>
    <origin xyz="0 0.0 -0.010" rpy="0 0 0"/>
    <geometry>
      <box size="0.2 0.12 0.02" />
    </geometry>
  </collision>
</link>
<gazebo reference="R_foot">
  <material>Gazebo/Red</material>
  <turnGravityOff>false</turnGravityOff>
</gazebo>

<joint name="R_leg3_joint" type="revolute" >
  <origin xyz="0 0.0 -0.250" rpy="0 0 0" />
  <parent link="R_leg" />
  <child link="R_foot" />
  <axis xyz="0 1 0"/>
  <limit effort="30" velocity="1" lower="-1.0" upper="1.0"/>
  <joint_properties damping="0.0" friction="0.0"/>
</joint>

<body:empty name="R_foot_force_model_name">
  <sensor:contact name="R_foot_contact_sensor">
    <updateRate>15.0</updateRate>
    <geom>R_foot</geom>
    <controller:gazebo_ros_bumper name="R_foot_contact_controller" plugin="libgazebo_ros_bumper.so">
      <alwaysOn>true</alwaysOn>
      <updateRate>15.0</updateRate>
      <bumperTopicName>R_foot_bumper</bumperTopicName>
      <interface:bumper name="dummy_bumper_iface" />
    </controller:gazebo_ros_bumper>
  </sensor:contact>
</body:empty>

Second Question : I dont understand how gazebo_ros_f3d works.. cause i get force and torque zero all the time... should it not show gravity as one of the forces... this is what i have written:

<controller:gazebo_ros_f3d name="gazebo_ros_Lf_force"plugin="libgazebo_ros_f3d.so">
  <alwaysOn>true</alwaysOn>
  <stepTime>0.001</stepTime>
  <updateRate>1000.0</updateRate>
  <bodyName>L_foot</bodyName>
  <topicName>L_foot_force</topicName>
  <frameName>map</frameName>
  <interface:position name="p3d_L_foot_force"/>
</controller:gazebo_ros_f3d>
edit retag flag offensive close merge delete

1 Answer

Sort by ยป oldest newest most voted
3

answered 2012-03-06 03:20:43 -0500

DimitriProsser gravatar image

updated 2012-03-06 08:57:28 -0500

<sensor:contact name="contact_sensor">
  <geom>base_link_geom</geom>
  <updateRate>20.0</updateRate>
  <controller:gazebo_ros_bumper name="gazebo_ros_bumper_controller" plugin="libgazebo_ros_bumper.so">
      <alwaysOn>true</alwaysOn>
      <updateRate>20.0</updateRate>
      <bumperTopicName>bumper</bumperTopicName>
      <interface:bumper name="bumper_iface" />
  </controller:gazebo_ros_bumper>
</sensor:contact>

The main thing you're missing is the <geom> tag that specifies what link will act as the bumper.

EDIT:

I've made my urdf example less generic. The <geom> tag is named based on the link you want to act as a bumper. This means that the name base_link_geom would make base_link a bumper. If you did front_right_wheel_geom, it would make front_right_wheel the bumper. You append "_geom" to the link name to set that link as your bumper.

edit flag offensive delete link more

Comments

Hi, i'm trying to add a contact bumper to my robot, I add a box a create a controller as you say here. Currently I had a /bumper/state topic been published but the states[] are empty all the time (even if I collide my robot with a wall). What should be the output of this topic?

jrcapriles gravatar image jrcapriles  ( 2012-04-12 06:20:04 -0500 )edit

Your robot must have collision for this to work.

DimitriProsser gravatar image DimitriProsser  ( 2012-04-13 03:36:32 -0500 )edit

hii, I added a contact sensor to my model but cannot find it in the rostopic list. I installed gazebo_ros_control package, is it enough or should I install any other.. please help me..

Mrudul gravatar image Mrudul  ( 2018-07-08 04:09:53 -0500 )edit

Question Tools

1 follower

Stats

Asked: 2012-03-05 14:38:32 -0500

Seen: 4,346 times

Last updated: Sep 27 '21