Skip to content

ROS 2 Migration: IMU Sensors

Leander Stephen D'Souza edited this page Jun 26, 2022 · 4 revisions

Overview

This pages describes the changes the imu sensor plugins in gazebo_plugins for ROS2, including a guide to migrate.

gazebo_ros_imu

This plugin has been removed in ROS2, as the same functionality can be had through gazebo_ros_imu_sensor. Please see that section instead.

gazebo_ros_imu_sensor

  • The <rpyOffset>/<xyzOffset> flags have been removed, instead, create a new link in your robot model with this offset and attach the sensor to this link
  • <frameName> has been renamed to <frame_name>. Without this set, the frame will default to the sensor's parent link name.
  • <initialOrientationAsReference> has been renamed to <initial_orientation_as_reference>. This should be set to false to comply with REP 145. This parameter was added in ros-simulation/gazebo_ros_pkgs#1051.
  • <updateRateHz>/<updateRate> has been removed. Instead, set the update rate in the sensor's SDF
  • <robotNamespace> has been removed, instead use <namespace>my_namespace</namespace>within the <ros> tag for the plugin.
  • <topicName> has been removed. Instead, use a remapping rule <remapping>~/out:=my_new_topic<remapping> within the <ros> tag for the plugin.
  • <gaussianNoise> has been removed. Instead, set noise in the sensor. Currently, noise on orientation is not supported. If you need this feature, consider adding it to gazebo.
  • <always_on>true</always_on> is still required in the sensor's SDF.

Example Migration

ROS1

<link name="my_link">
  ...
  <sensor name="my_imu" type="imu">
    <always_on>true</always_on>
    <plugin name="my_imu_plugin" filename="libgazebo_ros_imu_sensor.so">
      <topicName>/imu/data</topicName>
      <!-- Publish at 30 hz -->
      <updateRate>30</updateRate>
      <frameName>my_link</frameName>
    </plugin>
  </sensor>
</link>

ROS2

<link name="my_link">
  ...
  <sensor name="my_imu" type="imu">
    <always_on>true</always_on>
    <!-- Publish at 30 hz -->
    <update_rate>30</update_rate>
    <plugin name="my_imu_plugin" filename="libgazebo_ros_imu_sensor.so">
      <ros>
        <!-- Will publish to /imu/data -->
        <namespace>/imu</namespace>
        <remapping>~/out:=data</remapping>
      </ros>
      <!-- frame_name ommited, will be "my_link" -->
    </plugin>
  </sensor>
</link>