19 #ifndef __UUV_GAZEBO_PLUGINS_FIN_PLUGIN_HH__ 20 #define __UUV_GAZEBO_PLUGINS_FIN_PLUGIN_HH__ 22 #include <boost/scoped_ptr.hpp> 23 #include <gazebo/gazebo.hh> 26 #include <gazebo/msgs/msgs.hh> 30 #include "Double.pb.h" 35 typedef const boost::shared_ptr<const uuv_gazebo_plugins_msgs::msgs::Double>
47 public:
virtual void Load(physics::ModelPtr _model,
48 sdf::ElementPtr _sdf);
51 public:
virtual void Init();
55 public:
void OnUpdate(
const common::UpdateInfo &_info);
73 protected: transport::NodePtr
node;
76 protected: physics::JointPtr
joint;
79 protected: physics::LinkPtr
link;
transport::SubscriberPtr currentSubscriber
Subcriber to current message.
ignition::math::Vector3d finForce
Force component calculated from the lift and drag module.
double angle
Latest fin angle in [rad].
virtual void Load(physics::ModelPtr _model, sdf::ElementPtr _sdf)
double inputCommand
Latest input command.
const boost::shared_ptr< const uuv_gazebo_plugins_msgs::msgs::Double > ConstDoublePtr
Definition of a pointer to the floating point message.
physics::JointPtr joint
The fin joint.
ignition::math::Vector3d currentVelocity
Current velocity vector read from topic.
void OnUpdate(const common::UpdateInfo &_info)
Update the simulation state.
virtual ~FinPlugin()
Destructor.
Various Lift&Drag models for Fins.
common::Time angleStamp
Time stamp of latest thrust force.
void UpdateCurrentVelocity(ConstVector3dPtr &_msg)
Reads current velocity topic.
std::shared_ptr< Dynamics > dynamics
Fin dynamic model.
void UpdateInput(ConstDoublePtr &_msg)
Callback for the input topic subscriber.
transport::NodePtr node
Gazebo node.
std::string topicPrefix
Topic prefix.
physics::LinkPtr link
The fin link.
transport::SubscriberPtr commandSubscriber
Subscriber to the reference signal topic.
event::ConnectionPtr updateConnection
Update event.
transport::PublisherPtr anglePublisher
Publisher to the output thrust topic.
std::shared_ptr< LiftDrag > liftdrag
Lift&Drag model.