Skip to content

ROS 2 Migration: Ray sensors

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

Overview

In ROS2, a new plugin gazebo_ros_ray_sensor is being added to replace the functionality of the 4 plugins listed below. This plugin provides an interface to the output of a ray or gpu_ray gazebo sensor in ROS. The following guide lists the steps needed to migrate robots using the old plugins.

To provide the different outputs of these plugins, a parameter <output_type> is added to set the message type the plugin publishes.

Table of Contents

  1. Shared Migration Steps
  2. Additional steps for gazebo_ros_laser
  3. Additional steps for gazebo_ros_gpu_laser
  4. Additional steps for gazebo_ros_block_laser
  5. Additional steps for gazebo_ros_range

Shared

The following migration notes apply to all previous ray plugins:

  • ray vs gpu_ray: gazebo_ros_ray_sensor supports either the gazebo's ray or gpu_ray sensor for any output type. There are no longer different plugins for the two sensors!

  • Namespaces: <robotNamespace> has been replaced with <namespace>my_namespace</namespace> within the plugin's <ros> tag as per this guide. By default, the plugins will be in the root namespace.

  • Topic name: <topicName> has been replaced with remapping rules. Use <remapping>~/out:=my_topic</remapping> within the plugin's <ros> tag as per this guide.

  • TF Frame ID: The use of tf prefixes has been deprecated entirely. The TF frame will by default be the name of the link the sensor is attached to, but may be overridden by setting the <frame_name> tag.

  • Noise: The plugins no longer add noise using a <gaussianNoise> tag. Instead, set the noise tag with the sensor as demonstrated in the examples below.

  • Update rate: The <updateRate> tag is no longer supported. Instead, set the update_rate tag with the sensor as demonstrated in the examples below.

  • Output type: The <output_type> tag can take one of these values:

    • sensor_msgs/PointCloud2: 3D cloud of points (default)
    • sensor_msgs/PointCloud: 3D cloud of points
    • sensor_msgs/LaserScan: 2D scan, uses center vertical ray if there are multiple
    • sensor_msgs/Range: Single distance value, minimum of all ray ranges of parent sensor

gazebo_ros_laser

Additional Changes

  • If the sensor has multiple vertical rays, the published LaserScan will be the complete horizontal scan from the center vertical ray. In the ROS1 version, having multiple vertical rays would produce invalid output without warning/error.

  • You must add <output_type>sensor_msgs/LaserScan</output_type> for the plugin to publish a LaserScan rather than the default sensor_msgs/PointCloud2.

Example Migration

ROS1

<link name="hokuyo_link">
  <!-- Visuals / Collisions omitted for this example -->
  <sensor type="gpu_ray" name="head_hokuyo_sensor">
    <ray>
      <scan>
        <horizontal>
          <samples>720</samples>
          <resolution>1</resolution>
          <min_angle>-1.570796</min_angle>
          <max_angle>1.570796</max_angle>
        </horizontal>
      </scan>
      <range>
        <min>0.10</min>
        <max>30.0</max>
        <resolution>0.01</resolution>
      </range>
    </ray>
    <plugin name="gazebo_ros_head_hokuyo_controller" filename="libgazebo_ros_laser.so">
      <topicName>/rrbot/laser/scan</topicName>
      <frameName>hokuyo_link</frameName>
      <gaussianNoise>0.01</gaussianNoise>
      <updateRate>30</updateRate>
    </plugin>
  </sensor>
</link>

ROS2

<link name="hokuyo_link">
  <!-- Visuals / Collisions omitted for this example -->
  <sensor type="gpu_ray" name="head_hokuyo_sensor">
    <ray>
      <scan>
        <horizontal>
          <samples>720</samples>
          <resolution>1</resolution>
          <min_angle>-1.570796</min_angle>
          <max_angle>1.570796</max_angle>
        </horizontal>
      </scan>
      <range>
        <min>0.10</min>
        <max>30.0</max>
        <resolution>0.01</resolution>
      </range>
      <!-- Using gazebo's noise instead of plugin's -->
      <noise>
        <type>gaussian</type>
        <mean>0.0</mean>
        <stddev>0.01</stddev>
      </noise>
    </ray>
    <!-- Using gazebo's update rate instead of plugin's -->
    <update_rate>30</update_rate>

    <plugin name="gazebo_ros_head_hokuyo_controller" filename="libgazebo_ros_ray_sensor.so">
      <!-- Change namespace and output topic so published topic is /rrbot/laser/scan -->
      <ros>
        <namespace>/rrbot/laser</namespace>
        <remapping>~/out:=scan</remapping>
      </ros>
      <!-- Set output to sensor_msgs/LaserScan to get same output type as gazebo_ros_laser -->
      <output_type>sensor_msgs/LaserScan</output_type>
      <!-- <frame_name> ommited, will default to hokuo_link -->
    </plugin>
  </sensor>
</link>

gazebo_ros_gpu_laser

Additional Changes

Migration steps are the same as gazebo_ros_laser, just change the <sensor type="ray" ... to <sensor type="gpu_ray" ... to use the GPU for faster simulation. The gazebo_ros_ray_sensor plugin will work with either a ray or gpu_ray sensor.

gazebo_ros_block_laser

Additional Changes

  • If you prefer to continue using the legacy PointCloud rather than PointCloud2, you must add <output_type>sensor_msgs/PointCloud</output_type> to the plugin's SDF

  • The <hokuyoMinIntensity> tag has been replaced with <min_intensity>

Example Migration

ROS1

<link name="block_laser_link">
  <!-- Visuals / Collisions omitted for this example -->
  <sensor type="ray" name="block_laser_sensor">
    <ray>
      <scan>
        <horizontal>
          <samples>10</samples>
          <resolution>1</resolution>
          <min_angle>-0.523</min_angle>
          <max_angle>0.523</max_angle>
        </horizontal>
        <vertical>
          <samples>10</samples>
          <resolution>1</resolution>
          <min_angle>-0.523</min_angle>
          <max_angle>0.523</max_angle>
        </vertical>
      </scan>
      <range>
        <min>0.10</min>
        <max>5.0</max>
        <resolution>0.01</resolution>
      </range>
    </ray>
    <plugin name="gazebo_ros_block_laser_controller" filename="libgazebo_ros_block_laser.so">
      <topicName>/rrbot/laser/pointcloud</topicName>
      <frameName>block_laser_link</frameName>
      <gaussianNoise>0.01</gaussianNoise>
      <updateRate>30</updateRate>
      <hokuyoMinIntensity>100.0</hokuyoMinIntensity>
    </plugin>
  </sensor>
</link>

ROS2

<link name="block_laser_link">
  <!-- Visuals / Collisions omitted for this example -->
  <sensor type="ray" name="block_laser_sensor">
    <ray>
      <scan>
        <horizontal>
          <samples>10</samples>
          <resolution>1</resolution>
          <min_angle>-0.523</min_angle>
          <max_angle>0.523</max_angle>
        </horizontal>
        <vertical>
          <samples>10</samples>
          <resolution>1</resolution>
          <min_angle>-0.523</min_angle>
          <max_angle>0.523</max_angle>
        </vertical>
      </scan>
      <range>
        <min>0.10</min>
        <max>5.0</max>
        <resolution>0.01</resolution>
      </range>
      <!-- Using gazebo's noise instead of plugin's -->
      <noise>
        <type>gaussian</type>
        <mean>0.0</mean>
        <stddev>0.01</stddev>
      </noise>
    </ray>
    <!-- Using gazebo's update rate instead of plugin's -->
    <update_rate>30</update_rate>
    <plugin name="gazebo_ros_block_laser_controller" filename="libgazebo_ros_ray_sensor.so">
      <!-- Change namespace and output topic so published topic is /rrbot/laser/pointcloud -->
      <ros>
        <namespace>/rrbot/laser</namespace>
        <remapping>~/out:=pointcloud</remapping>
      </ros>
      <!-- Set output to sensor_msgs/PointCloud to get same output type as gazebo_ros_block_laser -->
      <output_type>sensor_msgs/PointCloud</output_type>
      <!-- <frame_name> ommited, will default to block_laser_link -->

      <!-- min_intensity instead of hokuyoMinIntensity -->
      <min_intensity>100.0</min_intensity>
    </plugin>
  </sensor>
</link>

gazebo_ros_range

Additional Changes

  • Users no longer set the <fov> tag to define the output range message's field of view. The field of view is instead set to the sensor's true field of view.

    • This is calculated as max(hDiff, vDiff), where hDiff and vDiff are the field of view of the horizontal and vertical rays.

      Note that users should have the same angle range in the horizontal and vertical rays to follow the convention in the sensor_msgs/Range message.

  • You must add <output_type>sensor_msgs/Range</output_type> for the plugin to publish a Range rather than the default sensor_msgs/PointCloud2.

Example Migration

ROS1

<link name="range_link">
  <!-- Visuals / Collisions omitted for this example -->
  <sensor type="gpu_ray" name="range_sensor">
    <ray>
      <scan>
        <horizontal>
          <samples>10</samples>
          <resolution>1</resolution>
          <min_angle>-0.087</min_angle>
          <max_angle>0.087</max_angle>
        </horizontal>
        <vertical>
          <samples>10</samples>
          <resolution>1</resolution>
          <min_angle>-0.087</min_angle>
          <max_angle>0.087</max_angle>
        </vertical>
      </scan>
      <range>
        <min>0.10</min>
        <max>5.0</max>
        <resolution>0.01</resolution>
      </range>
    </ray>
    <plugin name="gazebo_ros_range_controller" filename="libgazebo_ros_laser.so">
      <topicName>/rrbot/range</topicName>
      <frameName>range_link</frameName>
      <gaussianNoise>0.01</gaussianNoise>
      <updateRate>30</updateRate>
      <fov>0.17453293</fov>
    </plugin>
  </sensor>
</link>

ROS2

<link name="range_link">
  <!-- Visuals / Collisions omitted for this example -->
  <sensor type="gpu_ray" name="range_sensor">
    <ray>
      <scan>
        <horizontal>
          <samples>10</samples>
          <resolution>1</resolution>
          <min_angle>-0.087</min_angle>
          <max_angle>0.087</max_angle>
        </horizontal>
        <vertical>
          <samples>10</samples>
          <resolution>1</resolution>
          <min_angle>-0.087</min_angle>
          <max_angle>0.087</max_angle>
        </vertical>
      </scan>
      <range>
        <min>0.10</min>
        <max>5.0</max>
        <resolution>0.01</resolution>
      </range>
      <!-- Using gazebo's noise instead of plugin's -->
      <noise>
        <type>gaussian</type>
        <mean>0.0</mean>
        <stddev>0.01</stddev>
      </noise>
    </ray>
    <!-- Using gazebo's update rate instead of plugin's -->
    <update_rate>30</update_rate>
    <plugin name="gazebo_ros_range_controller" filename="libgazebo_ros_ray_sensor.so">
      <!-- Change namespace and output topic so published topic is /rrbot/laser/scan -->
      <ros>
        <namespace>/rrbot</namespace>
        <remapping>~/out:=range</remapping>
      </ros>
      <!-- Set output to sensor_msgs/Range to get same output type as gazebo_ros_range -->
      <output_type>sensor_msgs/Range</output_type>
      <!-- <frame_name> ommited, will default to range_link -->
    </plugin>
  </sensor>
</link>
Clone this wiki locally