Groud Truth Position Pose and Rates Interface

GazeboRosP3D controller. More...

Classes

class  gazebo::GazeboRosP3D
 GazeboRosP3D controller. More...

Detailed Description

GazeboRosP3D controller.

This controller requires to a model as its parent. The plugin broadcasts a body's pose and rates through ROS nav_msgs::Odometry message. In the example below, the plubin broadcasts pose and rate of a body named body_name over ROS topic name body_pose_groud_truth.

Example Usage:

     <model:physical name="some_fancy_model">
       <controller:gazebo_ros_p3d name="p3d_controller" plugin="libgazebo_ros_p3d.so">
         <alwaysOn>true</alwaysOn>
         <updateRate>1000.0</updateRate>
         <bodyName>body_name</bodyName>
         <topicName>body_pose_ground_truth</topicName>
         <frameName>map</frameName>
         <xyzOffsets>25.65 25.65 0</xyzOffsets> <!-- option to initialize odometry for fake localization-->
         <rpyOffsets>0 0 0</rpyOffsets>
         <interface:position name="p3d_position_iface"/>
       </controller:gazebo_ros_p3d>
     </model:phyiscal>
   
 All Classes Namespaces Files Functions Variables Typedefs Enumerator Friends Defines


gazebo_plugins
Author(s): Sachin Chitta, Stu Glaser, John Hsu
autogenerated on Fri Jan 11 10:09:31 2013