PoseGTROSPlugin
class gazebo::PoseGTROSPlugin
¶
class gazebo::PoseGTROSPlugin : public gazebo::ROSBaseModelPlugin
Summary¶
Members | Descriptions |
---|---|
public PoseGTROSPlugin () |
Class constructor. |
public ~PoseGTROSPlugin () |
Class destructor. |
public virtual void Load (physics::ModelPtr _model,sdf::ElementPtr _sdf) |
Load the plugin. |
protected ros::Publisher nedOdomPub |
|
protected ignition::math::Pose3d offset |
Pose offset. |
protected std::string nedFrameID |
|
protected ignition::math::Pose3d nedTransform |
|
protected bool nedTransformIsInit |
|
protected bool publishNEDOdom |
|
protected tf2_ros::Buffer tfBuffer |
|
protected boost::shared_ptr< tf2_ros::TransformListener > tfListener |
|
protected ignition::math::Vector3d lastLinVel |
|
protected ignition::math::Vector3d lastAngVel |
|
protected ignition::math::Vector3d linAcc |
|
protected ignition::math::Vector3d angAcc |
|
protected ignition::math::Vector3d lastRefLinVel |
|
protected ignition::math::Vector3d lastRefAngVel |
|
protected ignition::math::Vector3d refLinAcc |
|
protected ignition::math::Vector3d refAngAcc |
|
protected virtual bool OnUpdate (const common::UpdateInfo & _info) |
Update sensor measurement. |
protected void PublishNEDOdomMessage (common::Time _time,ignition::math::Pose3d _pose,ignition::math::Vector3d _linVel,ignition::math::Vector3d _angVel) |
|
protected void PublishOdomMessage (common::Time _time,ignition::math::Pose3d _pose,ignition::math::Vector3d _linVel,ignition::math::Vector3d _angVel) |
|
protected void UpdateNEDTransform () |
Members¶
public
PoseGTROSPlugin
()
¶
Class constructor.
public
~PoseGTROSPlugin
()
¶
Class destructor.
public virtual void
Load
(physics::ModelPtr _model,sdf::ElementPtr _sdf)
¶
Load the plugin.
protected ros::Publisher
nedOdomPub
¶
protected ignition::math::Pose3d
offset
¶
Pose offset.
protected std::string
nedFrameID
¶
protected ignition::math::Pose3d
nedTransform
¶
protected bool
nedTransformIsInit
¶
protected bool
publishNEDOdom
¶
protected tf2_ros::Buffer
tfBuffer
¶
protected boost::shared_ptr< tf2_ros::TransformListener >
tfListener
¶
protected ignition::math::Vector3d
lastLinVel
¶
protected ignition::math::Vector3d
lastAngVel
¶
protected ignition::math::Vector3d
linAcc
¶
protected ignition::math::Vector3d
angAcc
¶
protected ignition::math::Vector3d
lastRefLinVel
¶
protected ignition::math::Vector3d
lastRefAngVel
¶
protected ignition::math::Vector3d
refLinAcc
¶
protected ignition::math::Vector3d
refAngAcc
¶
protected virtual bool
OnUpdate
(const common::UpdateInfo & _info)
¶
Update sensor measurement.