Class GazeboRosRaySensor

Inheritance Relationships

Base Type

  • public SensorPlugin

Class Documentation

class gazebo_plugins::GazeboRosRaySensor : public SensorPlugin

Plugin to attach to a gazebo ray or gpu_ray sensor and publish its data to ROS.

SDF parameters:

<output_type>: Optional. The message type of the plugin's output. Can be any of the following:
  * 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

<frame_name>: TF Frame id of output header.
             If not set, frame id will be name of sensor's parent link

<min_intensity>: Clip intensity values for output to this value.
                Default: 0.0

<radiation_type>: The radiation type to publish when the output type is sensor_msgs/Range.
                 Can be either "infrared" or "ultrasonic".
                 Default: "infrared".

Example SDF:

<plugin name="my_ray_sensor_plugin" filename="libgazebo_ros_ray_sensor.so">
  <ros>
    <!-- Configure namespace and remap to publish to /ray/pointcloud2 -->
    <namespace>/ray</namespace>
    <remapping>~/out:=pointcloud2</remapping>
  </ros>
  <!-- Output as a PointCloud2, see above for other types -->
  <output_type>sensor_msgs/PointCloud2</output_type>
  <!-- Clip intensity values so all are above 100, optional -->
  <min_intensity>100.0</min_intensity>
  <!-- Frame id for header of output, defaults to sensor's parent link name -->
  <frame_name>ray_link</frame_name>
</plugin>

Public Functions

GazeboRosRaySensor()

Constructor.

virtual ~GazeboRosRaySensor()

Destructor.

void Load(gazebo::sensors::SensorPtr _parent, sdf::ElementPtr _sdf)