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

#include <FinPlugin.hh>

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

Public Member Functions

 FinPlugin ()
 Constructor. More...
 
virtual void Init ()
 
virtual void Load (physics::ModelPtr _model, sdf::ElementPtr _sdf)
 
void OnUpdate (const common::UpdateInfo &_info)
 Update the simulation state. More...
 
virtual ~FinPlugin ()
 Destructor. More...
 

Protected Member Functions

void UpdateCurrentVelocity (ConstVector3dPtr &_msg)
 Reads current velocity topic. More...
 
void UpdateInput (ConstDoublePtr &_msg)
 Callback for the input topic subscriber. More...
 

Protected Attributes

double angle
 Latest fin angle in [rad]. More...
 
transport::PublisherPtr anglePublisher
 Publisher to the output thrust topic. More...
 
common::Time angleStamp
 Time stamp of latest thrust force. More...
 
transport::SubscriberPtr commandSubscriber
 Subscriber to the reference signal topic. More...
 
transport::SubscriberPtr currentSubscriber
 Subcriber to current message. More...
 
ignition::math::Vector3d currentVelocity
 Current velocity vector read from topic. More...
 
std::shared_ptr< Dynamicsdynamics
 Fin dynamic model. More...
 
ignition::math::Vector3d finForce
 Force component calculated from the lift and drag module. More...
 
int finID
 Fin ID. More...
 
double inputCommand
 Latest input command. More...
 
physics::JointPtr joint
 The fin joint. More...
 
std::shared_ptr< LiftDragliftdrag
 Lift&Drag model. More...
 
physics::LinkPtr link
 The fin link. More...
 
transport::NodePtr node
 Gazebo node. More...
 
std::string topicPrefix
 Topic prefix. More...
 
event::ConnectionPtr updateConnection
 Update event. More...
 

Detailed Description

Definition at line 38 of file FinPlugin.hh.

Constructor & Destructor Documentation

gazebo::FinPlugin::FinPlugin ( )

Constructor.

Definition at line 30 of file FinPlugin.cc.

gazebo::FinPlugin::~FinPlugin ( )
virtual

Destructor.

Definition at line 35 of file FinPlugin.cc.

Member Function Documentation

void gazebo::FinPlugin::Init ( )
virtual

Definition at line 132 of file FinPlugin.cc.

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

Definition at line 48 of file FinPlugin.cc.

void gazebo::FinPlugin::OnUpdate ( const common::UpdateInfo &  _info)

Update the simulation state.

Parameters
[in]_infoInformation used in the update event.

Definition at line 137 of file FinPlugin.cc.

void gazebo::FinPlugin::UpdateCurrentVelocity ( ConstVector3dPtr &  _msg)
protected

Reads current velocity topic.

Definition at line 195 of file FinPlugin.cc.

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

Callback for the input topic subscriber.

Definition at line 189 of file FinPlugin.cc.

Member Data Documentation

double gazebo::FinPlugin::angle
protected

Latest fin angle in [rad].

Definition at line 100 of file FinPlugin.hh.

transport::PublisherPtr gazebo::FinPlugin::anglePublisher
protected

Publisher to the output thrust topic.

Definition at line 85 of file FinPlugin.hh.

common::Time gazebo::FinPlugin::angleStamp
protected

Time stamp of latest thrust force.

Definition at line 103 of file FinPlugin.hh.

transport::SubscriberPtr gazebo::FinPlugin::commandSubscriber
protected

Subscriber to the reference signal topic.

Definition at line 82 of file FinPlugin.hh.

transport::SubscriberPtr gazebo::FinPlugin::currentSubscriber
protected

Subcriber to current message.

Definition at line 106 of file FinPlugin.hh.

ignition::math::Vector3d gazebo::FinPlugin::currentVelocity
protected

Current velocity vector read from topic.

Definition at line 109 of file FinPlugin.hh.

std::shared_ptr<Dynamics> gazebo::FinPlugin::dynamics
protected

Fin dynamic model.

Definition at line 64 of file FinPlugin.hh.

ignition::math::Vector3d gazebo::FinPlugin::finForce
protected

Force component calculated from the lift and drag module.

Definition at line 88 of file FinPlugin.hh.

int gazebo::FinPlugin::finID
protected

Fin ID.

Definition at line 94 of file FinPlugin.hh.

double gazebo::FinPlugin::inputCommand
protected

Latest input command.

Definition at line 91 of file FinPlugin.hh.

physics::JointPtr gazebo::FinPlugin::joint
protected

The fin joint.

Definition at line 76 of file FinPlugin.hh.

std::shared_ptr<LiftDrag> gazebo::FinPlugin::liftdrag
protected

Lift&Drag model.

Definition at line 67 of file FinPlugin.hh.

physics::LinkPtr gazebo::FinPlugin::link
protected

The fin link.

Definition at line 79 of file FinPlugin.hh.

transport::NodePtr gazebo::FinPlugin::node
protected

Gazebo node.

Definition at line 73 of file FinPlugin.hh.

std::string gazebo::FinPlugin::topicPrefix
protected

Topic prefix.

Definition at line 97 of file FinPlugin.hh.

event::ConnectionPtr gazebo::FinPlugin::updateConnection
protected

Update event.

Definition at line 70 of file FinPlugin.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 Thu Jun 18 2020 03:28:24