gazebo-yarp-plugins
Gazebo Plugins exposing YARP interfaces.
|
Gazebo Plugin that publishes the pose of the root link of a model with respect to the Gazebo world frame. More...
#include <ModelPosePublisher.hh>
Public Member Functions | |
~GazeboYarpModelPosePublisher () | |
void | Load (gazebo::physics::ModelPtr, sdf::ElementPtr) |
Store pointer to the model, load parameters from the SDF, configure the frame transform client, reset the time of the last update and connect to the World update event of Gazebo. | |
Gazebo Plugin that publishes the pose of the root link of a model with respect to the Gazebo world frame.
This plugin instantiates a yarp::dev::FrameTransformClient
in order to publish the transform between the Gazebo world frame and the root link of the model. This requires a yarp::dev::FrameTransformServer
to be actived and running before the model is inserted in Gazebo. It is not required to write code in order to have a working FrameTransfomServer
. Instead yarpdev
can be used from the command line, e.g.
In the example above support to ROS is disabled.
Each transform published by the plugin contains as source
frame the string "/inertial" and as target
frame a string that depends on the name
option of the model
tag within the SDF. If such a name is <name>
the string describing the target
will be "/<name>/frame". In case the model <name>
is inserted in the Gazebo environment more than once than the its name becomes <name>_x
where x
assumes the values 0, 1, 2...
. This beavior depends on the internal behavior of Gazebo.
The pose published by the plugin is that of the root link of the model with respect to the Gazebo world frame. If the SDF of the model is the following
then the pose of the root link depends on both the transformation between the Gazebo world frame and the model frame and the transformation between the model frame and the root link.
In order to retrieve the published transform an istance of yarp::dev::FrameTransformClient
can be used. An example is provided below
The update rate of the plugin can be configured using the period
SDF tag in seconds. If the parameter is not provided a default value of 10 ms is used.
This plugin does not support Gazebo nested models since the method gazebo::physics::WorldPose()
does not work properly with nested models (see [issue](https://github.com/osrf/gazebo/issues/2410")).
gazebo::GazeboYarpModelPosePublisher::~GazeboYarpModelPosePublisher | ( | ) |
void gazebo::GazeboYarpModelPosePublisher::Load | ( | gazebo::physics::ModelPtr | _parent, |
sdf::ElementPtr | _sdf ) |
Store pointer to the model, load parameters from the SDF, configure the frame transform client, reset the time of the last update and connect to the World update event of Gazebo.