Public Member Functions | Protected Member Functions | Protected Attributes | List of all members
gazebo::ThrusterPlugin Class Reference

Class for the thruster plugin. More...

#include <ThrusterPlugin.hh>

Inheritance diagram for gazebo::ThrusterPlugin:
Inheritance graph
[legend]

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< ConversionFunctionconversionFunction
 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< DynamicsthrusterDynamics
 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...
 

Detailed Description

Class for the thruster plugin.

Definition at line 45 of file ThrusterPlugin.hh.

Constructor & Destructor Documentation

gazebo::ThrusterPlugin::ThrusterPlugin ( )

Constructor.

Definition at line 42 of file ThrusterPlugin.cc.

gazebo::ThrusterPlugin::~ThrusterPlugin ( )
virtual

Destructor.

Definition at line 57 of file ThrusterPlugin.cc.

Member Function Documentation

void gazebo::ThrusterPlugin::Init ( )
virtual

Definition at line 192 of file ThrusterPlugin.cc.

void gazebo::ThrusterPlugin::Load ( physics::ModelPtr  _model,
sdf::ElementPtr  _sdf 
)
virtual

Definition at line 70 of file ThrusterPlugin.cc.

void gazebo::ThrusterPlugin::Reset ( )
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.

Parameters
[in]_infoInformation used in the update event.

Definition at line 203 of file ThrusterPlugin.cc.

void gazebo::ThrusterPlugin::UpdateInput ( ConstDoublePtr _msg)
protected

Callback for the input topic subscriber.

Definition at line 256 of file ThrusterPlugin.cc.

Member Data Documentation

double gazebo::ThrusterPlugin::clampMax
protected

: Optional: Commands greater than this value will be clamped.

Definition at line 108 of file ThrusterPlugin.hh.

double gazebo::ThrusterPlugin::clampMin
protected

: Optional: Commands less than this value will be clamped.

Definition at line 105 of file ThrusterPlugin.hh.

transport::SubscriberPtr gazebo::ThrusterPlugin::commandSubscriber
protected

Subscriber to the reference signal topic.

Definition at line 86 of file ThrusterPlugin.hh.

std::shared_ptr<ConversionFunction> gazebo::ThrusterPlugin::conversionFunction
protected

Thruster conversion function.

Definition at line 74 of file ThrusterPlugin.hh.

double gazebo::ThrusterPlugin::gain
protected

: Optional: Gain factor: Desired angular velocity = command * gain

Definition at line 123 of file ThrusterPlugin.hh.

double gazebo::ThrusterPlugin::inputCommand
protected

Input command, typically desired angular velocity of the rotor.

Definition at line 93 of file ThrusterPlugin.hh.

bool gazebo::ThrusterPlugin::isOn
protected

Optional: Flag to indicate if the thruster is turned on or off.

Definition at line 126 of file ThrusterPlugin.hh.

physics::JointPtr gazebo::ThrusterPlugin::joint
protected

Optional: The rotor joint, used for visualization.

Definition at line 102 of file ThrusterPlugin.hh.

transport::NodePtr gazebo::ThrusterPlugin::node
protected

Gazebo node.

Definition at line 83 of file ThrusterPlugin.hh.

double gazebo::ThrusterPlugin::propellerEfficiency
protected

Optional: Propeller angular velocity efficiency term.

Definition at line 132 of file ThrusterPlugin.hh.

double gazebo::ThrusterPlugin::thrustEfficiency
protected

Optional: Output thrust efficiency factor of the thruster.

Definition at line 129 of file ThrusterPlugin.hh.

ignition::math::Vector3d gazebo::ThrusterPlugin::thrusterAxis
protected

The axis about which the thruster rotates.

Definition at line 135 of file ThrusterPlugin.hh.

std::shared_ptr<Dynamics> gazebo::ThrusterPlugin::thrusterDynamics
protected

Thruster dynamic model.

Definition at line 71 of file ThrusterPlugin.hh.

int gazebo::ThrusterPlugin::thrusterID
protected

Thruster ID, used to generated topic names automatically.

Definition at line 117 of file ThrusterPlugin.hh.

physics::LinkPtr gazebo::ThrusterPlugin::thrusterLink
protected

Pointer to the thruster link.

Definition at line 80 of file ThrusterPlugin.hh.

double gazebo::ThrusterPlugin::thrustForce
protected

Latest thrust force in [N].

Definition at line 96 of file ThrusterPlugin.hh.

common::Time gazebo::ThrusterPlugin::thrustForceStamp
protected

Time stamp of latest thrust force.

Definition at line 99 of file ThrusterPlugin.hh.

double gazebo::ThrusterPlugin::thrustMax
protected

: Optional: Maximum thrust force output

Definition at line 114 of file ThrusterPlugin.hh.

double gazebo::ThrusterPlugin::thrustMin
protected

: Optional: Minimum thrust force output

Definition at line 111 of file ThrusterPlugin.hh.

transport::PublisherPtr gazebo::ThrusterPlugin::thrustTopicPublisher
protected

Publisher to the output thrust topic.

Definition at line 89 of file ThrusterPlugin.hh.

std::string gazebo::ThrusterPlugin::topicPrefix
protected

Thruster topics prefix.

Definition at line 120 of file ThrusterPlugin.hh.

event::ConnectionPtr gazebo::ThrusterPlugin::updateConnection
protected

Update event.

Definition at line 77 of file ThrusterPlugin.hh.


The documentation for this class was generated from the following files:


uuv_gazebo_plugins
Author(s): Musa Morena Marcusso Manhaes , Sebastian Scherer , Luiz Ricardo Douat
autogenerated on Mon Jul 1 2019 19:39:12