Class GazeboRosP3D

Inheritance Relationships

Base Type

  • public ModelPlugin

Class Documentation

class gazebo_plugins::GazeboRosP3D : public ModelPlugin

Broadcasts the inertial pose of an model’s link via a nav_msgs/Odometry message on a ROS topic.

Example Usage:

<plugin name="gazebo_ros_force" filename="libgazebo_ros_force.so">

  <ros>

    <!-- Add a namespace -->
    <namespace>/demo</namespace>

    <!-- Remap the default topic -->
    <remapping>odom:=p3d_demo</remapping>

  </ros>

  <!-- Name of the link within this model whose pose will be published -->
  <body_name>box_link</body_name>

  <!-- Name of another link within this model to use as a reference frame.
       Remove the tag to use the world as a reference. -->
  <frame_name>sphere_link</frame_name>

  <!-- Update rate in Hz, defaults to 0.0, which means as fast as possible -->
  <update_rate>1</update_rate>

  <!-- Translation offset to be added to the pose. -->
  <xyz_offset>10 10 10</xyz_offset>

  <!-- Rotation offset to be added to the pose, in Euler angles. -->
  <rpy_offset>0.1 0.1 0.1</rpy_offset>

  <!-- Standard deviation of the noise to be added to the reported velocities. -->
  <gaussian_noise>0.01</gaussian_noise>

</plugin>

Public Functions

GazeboRosP3D()

Constructor.

virtual ~GazeboRosP3D()

Destructor.

void Load(gazebo::physics::ModelPtr _parent, sdf::ElementPtr _sdf) override