PoseGTROSPlugin
class gazebo::PoseGTROSPlugin¶
class gazebo::PoseGTROSPlugin : public gazebo::ROSBaseModelPlugin
Summary¶
| Members | Descriptions |
|---|---|
publicPoseGTROSPlugin() |
Class constructor. |
public~PoseGTROSPlugin() |
Class destructor. |
public virtual voidLoad(physics::ModelPtr _model,sdf::ElementPtr _sdf) |
Load the plugin. |
protected ros::PublishernedOdomPub |
|
protected ignition::math::Pose3doffset |
Pose offset. |
protected std::stringnedFrameID |
|
protected ignition::math::Pose3dnedTransform |
|
protected boolnedTransformIsInit |
|
protected boolpublishNEDOdom |
|
protected tf2_ros::BuffertfBuffer |
|
protected boost::shared_ptr< tf2_ros::TransformListener >tfListener |
|
protected ignition::math::Vector3dlastLinVel |
|
protected ignition::math::Vector3dlastAngVel |
|
protected ignition::math::Vector3dlinAcc |
|
protected ignition::math::Vector3dangAcc |
|
protected ignition::math::Vector3dlastRefLinVel |
|
protected ignition::math::Vector3dlastRefAngVel |
|
protected ignition::math::Vector3drefLinAcc |
|
protected ignition::math::Vector3drefAngAcc |
|
protected virtual boolOnUpdate(const common::UpdateInfo & _info) |
Update sensor measurement. |
protected voidPublishNEDOdomMessage(common::Time _time,ignition::math::Pose3d _pose,ignition::math::Vector3d _linVel,ignition::math::Vector3d _angVel) |
|
protected voidPublishOdomMessage(common::Time _time,ignition::math::Pose3d _pose,ignition::math::Vector3d _linVel,ignition::math::Vector3d _angVel) |
|
protected voidUpdateNEDTransform() |
Members¶
publicPoseGTROSPlugin()¶
Class constructor.
public~PoseGTROSPlugin()¶
Class destructor.
public virtual voidLoad(physics::ModelPtr _model,sdf::ElementPtr _sdf)¶
Load the plugin.
protected ros::PublishernedOdomPub¶
protected ignition::math::Pose3doffset¶
Pose offset.
protected std::stringnedFrameID¶
protected ignition::math::Pose3dnedTransform¶
protected boolnedTransformIsInit¶
protected boolpublishNEDOdom¶
protected tf2_ros::BuffertfBuffer¶
protected boost::shared_ptr< tf2_ros::TransformListener >tfListener¶
protected ignition::math::Vector3dlastLinVel¶
protected ignition::math::Vector3dlastAngVel¶
protected ignition::math::Vector3dlinAcc¶
protected ignition::math::Vector3dangAcc¶
protected ignition::math::Vector3dlastRefLinVel¶
protected ignition::math::Vector3dlastRefAngVel¶
protected ignition::math::Vector3drefLinAcc¶
protected ignition::math::Vector3drefAngAcc¶
protected virtual boolOnUpdate(const common::UpdateInfo & _info)¶
Update sensor measurement.