16 #ifndef __ROS_BASE_MODEL_PLUGIN_HH__ 17 #define __ROS_BASE_MODEL_PLUGIN_HH__ 19 #include <gazebo/common/Plugin.hh> 20 #include <gazebo/gazebo.hh> 21 #include <gazebo/physics/physics.hh> 27 #include <tf/tfMessage.h> 43 protected:
virtual void Load(physics::ModelPtr _model,
44 sdf::ElementPtr _sdf);
47 protected:
virtual bool OnUpdate(
const common::UpdateInfo&);
50 protected: physics::ModelPtr
model;
53 protected: physics::LinkPtr
link;
72 #endif // __ROS_BASE_MODEL_PLUGIN_HH__
tf::StampedTransform tfLocalNEDFrame
Local NED TF frame.
bool enableLocalNEDFrame
True if a the local NED frame needs to be broadcasted.
void SendLocalNEDTransform()
Returns true if the base_link_ned frame exists.
virtual void Load(physics::ModelPtr _model, sdf::ElementPtr _sdf)
Load plugin and its configuration from sdf,.
ignition::math::Pose3d localNEDFrame
Pose of the local NED frame wrt link frame.
physics::LinkPtr link
Pointer to the link.
ROSBaseModelPlugin()
Class constructor.
physics::ModelPtr model
Pointer to the model.
tf::TransformBroadcaster * tfBroadcaster
TF broadcaster for the local NED frame.
virtual bool OnUpdate(const common::UpdateInfo &)
Update callback from simulation.
virtual ~ROSBaseModelPlugin()
Class destructor.