19 #ifndef __UUV_GAZEBO_PLUGINS_THRUSTER_PLUGIN_HH__ 20 #define __UUV_GAZEBO_PLUGINS_THRUSTER_PLUGIN_HH__ 22 #include <boost/scoped_ptr.hpp> 28 #include <gazebo/gazebo.hh> 29 #include <gazebo/transport/TransportTypes.hh> 36 #include "Double.pb.h" 41 typedef const boost::shared_ptr<const uuv_gazebo_plugins_msgs::msgs::Double>
54 public:
virtual void Load(physics::ModelPtr _model,
55 sdf::ElementPtr _sdf);
58 public:
virtual void Init();
61 public:
virtual void Reset();
65 public:
void Update(
const common::UpdateInfo &_info);
83 protected: transport::NodePtr
node;
138 #endif // __UUV_GAZEBO_PLUGINS_THRUSTER_PLUGIN_HH__ void Update(const common::UpdateInfo &_info)
Update the simulation state.
virtual ~ThrusterPlugin()
Destructor.
double clampMax
: Optional: Commands greater than this value will be clamped.
physics::LinkPtr thrusterLink
Pointer to the thruster link.
physics::JointPtr joint
Optional: The rotor joint, used for visualization.
bool isOn
Optional: Flag to indicate if the thruster is turned on or off.
double propellerEfficiency
Optional: Propeller angular velocity efficiency term.
transport::PublisherPtr thrustTopicPublisher
Publisher to the output thrust topic.
const boost::shared_ptr< const uuv_gazebo_plugins_msgs::msgs::Double > ConstDoublePtr
Definition of a pointer to the floating point message.
std::shared_ptr< ConversionFunction > conversionFunction
Thruster conversion function.
common::Time thrustForceStamp
Time stamp of latest thrust force.
double clampMin
: Optional: Commands less than this value will be clamped.
double inputCommand
Input command, typically desired angular velocity of the rotor.
std::shared_ptr< Dynamics > thrusterDynamics
Thruster dynamic model.
virtual void Reset()
Custom plugin reset behavior.
double thrustMax
: Optional: Maximum thrust force output
transport::SubscriberPtr commandSubscriber
Subscriber to the reference signal topic.
transport::NodePtr node
Gazebo node.
double thrustMin
: Optional: Minimum thrust force output
Description of the conversion function fo a thruster.
int thrusterID
Thruster ID, used to generated topic names automatically.
double thrustEfficiency
Optional: Output thrust efficiency factor of the thruster.
Class for the thruster plugin.
ignition::math::Vector3d thrusterAxis
The axis about which the thruster rotates.
double gain
: Optional: Gain factor: Desired angular velocity = command * gain
void UpdateInput(ConstDoublePtr &_msg)
Callback for the input topic subscriber.
virtual void Load(physics::ModelPtr _model, sdf::ElementPtr _sdf)
event::ConnectionPtr updateConnection
Update event.
std::string topicPrefix
Thruster topics prefix.
ThrusterPlugin()
Constructor.
double thrustForce
Latest thrust force in [N].