Class for the thruster plugin. More...
#include <ThrusterPlugin.hh>

Public Member Functions | |
| virtual void | Init () |
| virtual void | Load (physics::ModelPtr _model, sdf::ElementPtr _sdf) |
| virtual void | Reset () |
| Custom plugin reset behavior. More... | |
| ThrusterPlugin () | |
| Constructor. More... | |
| void | Update (const common::UpdateInfo &_info) |
| Update the simulation state. More... | |
| virtual | ~ThrusterPlugin () |
| Destructor. More... | |
Protected Member Functions | |
| void | UpdateInput (ConstDoublePtr &_msg) |
| Callback for the input topic subscriber. More... | |
Protected Attributes | |
| double | clampMax |
| : Optional: Commands greater than this value will be clamped. More... | |
| double | clampMin |
| : Optional: Commands less than this value will be clamped. More... | |
| transport::SubscriberPtr | commandSubscriber |
| Subscriber to the reference signal topic. More... | |
| std::shared_ptr< ConversionFunction > | conversionFunction |
| Thruster conversion function. More... | |
| double | gain |
| : Optional: Gain factor: Desired angular velocity = command * gain More... | |
| double | inputCommand |
| Input command, typically desired angular velocity of the rotor. More... | |
| bool | isOn |
| Optional: Flag to indicate if the thruster is turned on or off. More... | |
| physics::JointPtr | joint |
| Optional: The rotor joint, used for visualization. More... | |
| transport::NodePtr | node |
| Gazebo node. More... | |
| double | propellerEfficiency |
| Optional: Propeller angular velocity efficiency term. More... | |
| double | thrustEfficiency |
| Optional: Output thrust efficiency factor of the thruster. More... | |
| ignition::math::Vector3d | thrusterAxis |
| The axis about which the thruster rotates. More... | |
| std::shared_ptr< Dynamics > | thrusterDynamics |
| Thruster dynamic model. More... | |
| int | thrusterID |
| Thruster ID, used to generated topic names automatically. More... | |
| physics::LinkPtr | thrusterLink |
| Pointer to the thruster link. More... | |
| double | thrustForce |
| Latest thrust force in [N]. More... | |
| common::Time | thrustForceStamp |
| Time stamp of latest thrust force. More... | |
| double | thrustMax |
| : Optional: Maximum thrust force output More... | |
| double | thrustMin |
| : Optional: Minimum thrust force output More... | |
| transport::PublisherPtr | thrustTopicPublisher |
| Publisher to the output thrust topic. More... | |
| std::string | topicPrefix |
| Thruster topics prefix. More... | |
| event::ConnectionPtr | updateConnection |
| Update event. More... | |
Class for the thruster plugin.
Definition at line 45 of file ThrusterPlugin.hh.
| gazebo::ThrusterPlugin::ThrusterPlugin | ( | ) |
Constructor.
Definition at line 42 of file ThrusterPlugin.cc.
|
virtual |
Destructor.
Definition at line 57 of file ThrusterPlugin.cc.
|
virtual |
Definition at line 192 of file ThrusterPlugin.cc.
|
virtual |
Definition at line 70 of file ThrusterPlugin.cc.
|
virtual |
Custom plugin reset behavior.
Definition at line 197 of file ThrusterPlugin.cc.
| void gazebo::ThrusterPlugin::Update | ( | const common::UpdateInfo & | _info | ) |
Update the simulation state.
| [in] | _info | Information used in the update event. |
Definition at line 203 of file ThrusterPlugin.cc.
|
protected |
Callback for the input topic subscriber.
Definition at line 256 of file ThrusterPlugin.cc.
|
protected |
: Optional: Commands greater than this value will be clamped.
Definition at line 108 of file ThrusterPlugin.hh.
|
protected |
: Optional: Commands less than this value will be clamped.
Definition at line 105 of file ThrusterPlugin.hh.
|
protected |
Subscriber to the reference signal topic.
Definition at line 86 of file ThrusterPlugin.hh.
|
protected |
Thruster conversion function.
Definition at line 74 of file ThrusterPlugin.hh.
|
protected |
: Optional: Gain factor: Desired angular velocity = command * gain
Definition at line 123 of file ThrusterPlugin.hh.
|
protected |
Input command, typically desired angular velocity of the rotor.
Definition at line 93 of file ThrusterPlugin.hh.
|
protected |
Optional: Flag to indicate if the thruster is turned on or off.
Definition at line 126 of file ThrusterPlugin.hh.
|
protected |
Optional: The rotor joint, used for visualization.
Definition at line 102 of file ThrusterPlugin.hh.
|
protected |
Gazebo node.
Definition at line 83 of file ThrusterPlugin.hh.
|
protected |
Optional: Propeller angular velocity efficiency term.
Definition at line 132 of file ThrusterPlugin.hh.
|
protected |
Optional: Output thrust efficiency factor of the thruster.
Definition at line 129 of file ThrusterPlugin.hh.
|
protected |
The axis about which the thruster rotates.
Definition at line 135 of file ThrusterPlugin.hh.
|
protected |
Thruster dynamic model.
Definition at line 71 of file ThrusterPlugin.hh.
|
protected |
Thruster ID, used to generated topic names automatically.
Definition at line 117 of file ThrusterPlugin.hh.
|
protected |
Pointer to the thruster link.
Definition at line 80 of file ThrusterPlugin.hh.
|
protected |
Latest thrust force in [N].
Definition at line 96 of file ThrusterPlugin.hh.
|
protected |
Time stamp of latest thrust force.
Definition at line 99 of file ThrusterPlugin.hh.
|
protected |
: Optional: Maximum thrust force output
Definition at line 114 of file ThrusterPlugin.hh.
|
protected |
: Optional: Minimum thrust force output
Definition at line 111 of file ThrusterPlugin.hh.
|
protected |
Publisher to the output thrust topic.
Definition at line 89 of file ThrusterPlugin.hh.
|
protected |
Thruster topics prefix.
Definition at line 120 of file ThrusterPlugin.hh.
|
protected |
Update event.
Definition at line 77 of file ThrusterPlugin.hh.