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

what does <body_name> and <frame_name> tag of gazebo IMU plugin imply?

asked 2020-09-24 01:51:34 -0500

Shiva_uchiha gravatar image

updated 2022-10-30 09:29:25 -0500

lucasw gravatar image

I am trying to implement a IMU sensor in gazebo using this tutorial :http://gazebosim.org/tutorials?tut=ros_gzplugins

 <gazebo reference="imu_link">
<gravity>true</gravity>
<sensor name="imu_sensor" type="imu">
  <always_on>true</always_on>
  <update_rate>100</update_rate>
  <visualize>true</visualize>
  <topic>__default_topic__</topic>
  <plugin filename="libgazebo_ros_imu_sensor.so" name="imu_plugin">
    <topicName>imu</topicName>
    <bodyName>imu_link</bodyName>
    <updateRateHZ>10.0</updateRateHZ>
    <gaussianNoise>0.0</gaussianNoise>
    <xyzOffset>0 0 0</xyzOffset>
    <rpyOffset>0 0 0</rpyOffset>
    <frameName>imu_link</frameName>
    <initialOrientationAsReference>false</initialOrientationAsReference>
  </plugin>
  <pose>0 0 0 0 0 0</pose>
</sensor>

</gazebo>

I am assuming that <frame_name> corresponds to the TF name of the link to which sensor is attached . However I am not sure what <body name=""> tag refers to.

It will be very helpful if some one can provide links to a more detailed page where all the tags are explained.

Thank you !

edit retag flag offensive close merge delete

1 Answer

Sort by ยป oldest newest most voted
1

answered 2020-09-27 05:44:17 -0500

Weasfas gravatar image

updated 2020-09-28 04:08:25 -0500

Hi @Shiva_uchiha,

First of all I want to clarify that the gazebo_ros_imu plugin is not the same as the gazebo_ros_imu_sensor plugin. The first one is a model plugin and the second one a sensor plugin, hence, they are attach to different things in the simulation.

Both use the frameName parameter to fill the sensor_msgs::Imu message header the plugins produce.

On the other hand, the bodyName name param is only used by the gazebo_ros_imu plugin to assert that the model to which the plugin is attached exists by that name in the Gazebo world. This has to be done like that to ensure the plugin is properly loaded in the model.

If you have doubts about its functioning you can check the github repo containing the implementation of all official Gazebo plugins here.

Hope it helps you.

Regards.

edit flag offensive delete link more

Question Tools

1 follower

Stats

Asked: 2020-09-24 01:51:34 -0500

Seen: 1,587 times

Last updated: Sep 28 '20