Skip to content

ROS 2 Migration: FT sensor

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

Overview

F3D and FTSensor plugins from ROS1 have been merged into gazebo_ros_ft_sensor in ROS2. This pages contains instructions on how to use FTSensor in ROS2 as FTSensor plugin in gazebo_plugins in ROS1.

Summary

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

SDF parameters

ROS 1 ROS 2
robotNamespace <ros><namespace>
jointName joint_name
topicName <ros><remapping>wrench:=custom_wrench</remapping></ros>
gaussianNoise gaussian_noise
updateRate update_rate

Example Migration

ROS1

    <model name='the_model'>
      ...

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

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

      <joint name="test_joint" type="revolute">
        ...
      </joint>

      <plugin name="gazebo_ros_ft" filename="libgazebo_ros_ft_sensor.so">

        <robotNamespace>demo</robotNamespace>
        <topicName>ft_sensor_demo</topicName>
        <jointName>test_joint</jointName>
        <updateRate>200</updateRate>
        <gaussianNoise>1.0</gaussianNoise>

      </plugin>

    </model>

ROS2

    <model name='the_model'>
      ...

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

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

      <joint name="test_joint" type="revolute">
        ...
      </joint>

      <plugin name="gazebo_ros_ft" filename="libgazebo_ros_ft_sensor.so">

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

        <!-- Replace camelCase elements with camel_case ones -->
        <joint_name>test_joint</joint_name>
        <update_rate>200</update_rate>
        <update_rate>1</update_rate>
        <gaussian_noise>0.01</gaussian_noise>

      </plugin>

    </model>