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

Gazebo model plugin class for underwater objects. More...

#include <UnderwaterObjectPlugin.hh>

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

Public Member Functions

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

Protected Member Functions

virtual void Connect ()
 Connects the update event callback. More...
 
virtual void GenWrenchMsg (ignition::math::Vector3d _force, ignition::math::Vector3d _torque, gazebo::msgs::WrenchStamped &_output)
 Returns the wrench message for debugging topics. More...
 
virtual void InitDebug (gazebo::physics::LinkPtr _link, gazebo::HydrodynamicModelPtr _hydro)
 Sets the topics used for publishing the intermediate data during the simulation. More...
 
virtual void PublishCurrentVelocityMarker ()
 Publish current velocity marker. More...
 
virtual void PublishHydrodynamicWrenches (gazebo::physics::LinkPtr _link)
 Publish hydrodynamic wrenches. More...
 
virtual void PublishIsSubmerged ()
 Publishes the state of the vehicle (is submerged) More...
 
virtual void PublishRestoringForce (gazebo::physics::LinkPtr _link)
 Publish restoring force. More...
 
void UpdateFlowVelocity (ConstVector3dPtr &_msg)
 Reads flow velocity topic. More...
 

Protected Attributes

std::string baseLinkName
 Name of vehicle's base_link. More...
 
gazebo::transport::SubscriberPtr flowSubscriber
 Subcriber to flow message. More...
 
ignition::math::Vector3d flowVelocity
 Flow velocity vector read from topic. More...
 
std::map< std::string, gazebo::transport::PublisherPtr > hydroPub
 Publishers of hydrodynamic and hydrostatic forces and torques in the case the debug flag is on. More...
 
gazebo::physics::ModelPtr model
 Pointer to the model structure. More...
 
std::map< gazebo::physics::LinkPtr, HydrodynamicModelPtrmodels
 Pairs of links & corresponding hydrodynamic models. More...
 
gazebo::transport::NodePtr node
 Gazebo node. More...
 
gazebo::event::ConnectionPtr updateConnection
 Update event. More...
 
bool useGlobalCurrent
 Flag to use the global current velocity or the individually assigned current velocity. More...
 
gazebo::physics::WorldPtr world
 Pointer to the world plugin. More...
 

Detailed Description

Gazebo model plugin class for underwater objects.

Definition at line 35 of file UnderwaterObjectPlugin.hh.

Constructor & Destructor Documentation

gazebo::UnderwaterObjectPlugin::UnderwaterObjectPlugin ( )

Constructor.

Definition at line 34 of file UnderwaterObjectPlugin.cc.

gazebo::UnderwaterObjectPlugin::~UnderwaterObjectPlugin ( )
virtual

Destructor.

Definition at line 39 of file UnderwaterObjectPlugin.cc.

Member Function Documentation

void gazebo::UnderwaterObjectPlugin::Connect ( )
protectedvirtual

Connects the update event callback.

Definition at line 221 of file UnderwaterObjectPlugin.cc.

void gazebo::UnderwaterObjectPlugin::GenWrenchMsg ( ignition::math::Vector3d  _force,
ignition::math::Vector3d  _torque,
gazebo::msgs::WrenchStamped &  _output 
)
protectedvirtual

Returns the wrench message for debugging topics.

Parameters
[in]_forceForce vector
[in]_torqueTorque vector
[in]_outputStamped wrench message to be updated

Definition at line 307 of file UnderwaterObjectPlugin.cc.

void gazebo::UnderwaterObjectPlugin::Init ( )
virtual

Definition at line 183 of file UnderwaterObjectPlugin.cc.

void gazebo::UnderwaterObjectPlugin::InitDebug ( gazebo::physics::LinkPtr  _link,
gazebo::HydrodynamicModelPtr  _hydro 
)
protectedvirtual

Sets the topics used for publishing the intermediate data during the simulation.

Parameters
[in]_linkPointer to the link
[in]_hydroPointer to the hydrodynamic model

Definition at line 158 of file UnderwaterObjectPlugin.cc.

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

Definition at line 49 of file UnderwaterObjectPlugin.cc.

void gazebo::UnderwaterObjectPlugin::PublishCurrentVelocityMarker ( )
protectedvirtual

Publish current velocity marker.

Definition at line 230 of file UnderwaterObjectPlugin.cc.

void gazebo::UnderwaterObjectPlugin::PublishHydrodynamicWrenches ( gazebo::physics::LinkPtr  _link)
protectedvirtual

Publish hydrodynamic wrenches.

Parameters
[in]_linkPointer to the link where the force information will be extracted from

Definition at line 273 of file UnderwaterObjectPlugin.cc.

void gazebo::UnderwaterObjectPlugin::PublishIsSubmerged ( )
protectedvirtual

Publishes the state of the vehicle (is submerged)

Definition at line 237 of file UnderwaterObjectPlugin.cc.

void gazebo::UnderwaterObjectPlugin::PublishRestoringForce ( gazebo::physics::LinkPtr  _link)
protectedvirtual

Publish restoring force.

Parameters
[in]_linkPointer to the link where the force information will be extracted from

Definition at line 255 of file UnderwaterObjectPlugin.cc.

void gazebo::UnderwaterObjectPlugin::Update ( const gazebo::common::UpdateInfo &  _info)
virtual

Update the simulation state.

Parameters
[in]_infoInformation used in the update event.

Definition at line 189 of file UnderwaterObjectPlugin.cc.

void gazebo::UnderwaterObjectPlugin::UpdateFlowVelocity ( ConstVector3dPtr &  _msg)
protected

Reads flow velocity topic.

Definition at line 244 of file UnderwaterObjectPlugin.cc.

Member Data Documentation

std::string gazebo::UnderwaterObjectPlugin::baseLinkName
protected

Name of vehicle's base_link.

Definition at line 113 of file UnderwaterObjectPlugin.hh.

gazebo::transport::SubscriberPtr gazebo::UnderwaterObjectPlugin::flowSubscriber
protected

Subcriber to flow message.

Definition at line 116 of file UnderwaterObjectPlugin.hh.

ignition::math::Vector3d gazebo::UnderwaterObjectPlugin::flowVelocity
protected

Flow velocity vector read from topic.

Definition at line 98 of file UnderwaterObjectPlugin.hh.

std::map<std::string, gazebo::transport::PublisherPtr> gazebo::UnderwaterObjectPlugin::hydroPub
protected

Publishers of hydrodynamic and hydrostatic forces and torques in the case the debug flag is on.

Definition at line 124 of file UnderwaterObjectPlugin.hh.

gazebo::physics::ModelPtr gazebo::UnderwaterObjectPlugin::model
protected

Pointer to the model structure.

Definition at line 107 of file UnderwaterObjectPlugin.hh.

std::map<gazebo::physics::LinkPtr, HydrodynamicModelPtr> gazebo::UnderwaterObjectPlugin::models
protected

Pairs of links & corresponding hydrodynamic models.

Definition at line 95 of file UnderwaterObjectPlugin.hh.

gazebo::transport::NodePtr gazebo::UnderwaterObjectPlugin::node
protected

Gazebo node.

Definition at line 110 of file UnderwaterObjectPlugin.hh.

gazebo::event::ConnectionPtr gazebo::UnderwaterObjectPlugin::updateConnection
protected

Update event.

Definition at line 101 of file UnderwaterObjectPlugin.hh.

bool gazebo::UnderwaterObjectPlugin::useGlobalCurrent
protected

Flag to use the global current velocity or the individually assigned current velocity.

Definition at line 120 of file UnderwaterObjectPlugin.hh.

gazebo::physics::WorldPtr gazebo::UnderwaterObjectPlugin::world
protected

Pointer to the world plugin.

Definition at line 104 of file UnderwaterObjectPlugin.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