Skip to content

ROS 2 Migration: Projector

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

Overview

This pages describes the changes in the projector plugin in gazebo_plugins for ROS 2, including a migration guide.

Summary

  • Currently, the only functionality of the plugin is to switch on/off a projector
  • The message type to toggle the projector has been changed to std_msgs/Bool from std_msgs/Int32. If true, the projector would be on and vice versa
  • projector tag has been divided into projector_link and projector_name.

SDF parameters

ROS 1 ROS 2
projector projector_link and projector_name
projectorTopicName <ros><remapping>switch:=custom_switch</remapping></ros>
robotNamespace
textureTopicName

Example Migration

ROS1

    <link name="projector_link">
      ...
      <projector name="texture_projector">
        <pose>0 0 0 0 0 0</pose>
        <texture>bricks.png</texture>
        <fov>0.959931088597</fov>
        <near_clip>0.1</near_clip>
        <far_clip>10</far_clip>
      </projector>
    </link>
    <static>true</static>
    <plugin name="projector_controller" filename="libgazebo_ros_projector.so">
      <robotNamespace>demo</robotNamespace>
      <projectorTopicName>switch_demo</projectorTopicName>
      <projector>projector_link/texture_projector</projector>
    </plugin>

ROS2

    <link name="projector_link">
      ...
      <projector name="texture_projector">
        <pose>0 0 0 0 0 0</pose>
        <texture>bricks.png</texture>
        <fov>0.959931088597</fov>
        <near_clip>0.1</near_clip>
        <far_clip>10</far_clip>
      </projector>
    </link>
    <static>true</static>
    <plugin name="projector_controller" filename="libgazebo_ros_projector.so">
      <ros>
        <!-- Remap for switch topic to be subscribed -->
        <namespace>/demo</namespace>
        <remapping>switch:=switch_demo</remapping>
      </ros>
      <projector_link>projector_link</projector_link>
      <projector_name>texture_projector</projector_name>
    </plugin>