Skip to content

ROS 2 Migration: P3D

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

Overview

This pages describes the changes in the P3D plugin in gazebo_plugins for ROS 2 and instructions for migration.

Summary

  • All SDF parameters are now snake_cased.
  • If the topic name is not defined, default to odom instead of failing.
  • tf_prefix is no longer supported.

SDF parameters

ROS 1 ROS 2
robotNamespace <ros><namespace>
bodyName body_name
topicName <ros><remapping>odom:=custom_odom</remapping></ros>
frameName frame_name
xyzOffset xyz_offset (prior to Galactic, use xyz_offsets)
rpyOffset rpy_offset (prior to Galactic, use rpy_offsets)
gaussianNoise gaussian_noise
updateRate update_rate

Example Migration

ROS1

    <model name='the_model'>
      ...

      <link name='box_link'>
        ...
      </link>

      <link name='sphere_link'>
        ...
      </link>

      <plugin name="gazebo_ros_p3d" filename="libgazebo_ros_p3d.so">

        <robotNamespace>demo</robotNamespace>
        <topicName>p3d_demo</topicName>
        <bodyName>box_link</bodyName>
        <frameName>sphere_link</frameName>
        <updateRate>1</updateRate>
        <xyzOffset>10 10 10</xyzOffset>
        <rpyOffset>0.1 0.1 0.1</rpyOffset>
        <gaussianNoise>0.01</gaussianNoise>

      </plugin>

    </model>

ROS2

    <model name='the_model'>
      ...

      <link name='box_link'>
        ...
      </link>

      <link name='sphere_link'>
        ...
      </link>

      <plugin name="gazebo_ros_p3d" filename="libgazebo_ros_p3d.so">

        <ros>
          <!-- Add namespace and remap the default topic -->
          <namespace>/demo</namespace>
          <remapping>odom:=p3d_demo</remapping>
        </ros>

        <!-- Replace camelCase elements with camel_case ones -->
        <body_name>box_link</body_name>
        <frame_name>sphere_link</frame_name>
        <update_rate>1</update_rate>
        <xyz_offset>10 10 10</xyz_offset>
        <rpy_offset>0.1 0.1 0.1</rpy_offset>
        <gaussian_noise>0.01</gaussian_noise>

      </plugin>


    </model>