Skip to content

UnderwaterObjectPlugin

class gazebo::UnderwaterObjectPlugin

class gazebo::UnderwaterObjectPlugin
  : public ModelPlugin

Gazebo model plugin class for underwater objects.

Summary
Members Descriptions
publicUnderwaterObjectPlugin() Constructor.
public virtual~UnderwaterObjectPlugin() Destructor.
public virtual voidLoad(gazebo::physics::ModelPtr _model,sdf::ElementPtr _sdf)
public virtual voidInit()
public virtual voidUpdate(const gazebo::common::UpdateInfo & _info) Update the simulation state.
protected std::map< gazebo::physics::LinkPtr,HydrodynamicModelPtr>models Pairs of links & corresponding hydrodynamic models.
protected ignition::math::Vector3dflowVelocity Flow velocity vector read from topic.
protected gazebo::event::ConnectionPtrupdateConnection Update event.
protected gazebo::physics::WorldPtrworld Pointer to the world plugin.
protected gazebo::physics::ModelPtrmodel Pointer to the model structure.
protected gazebo::transport::NodePtrnode Gazebo node.
protected std::stringbaseLinkName Name of vehicle's base_link.
protected gazebo::transport::SubscriberPtrflowSubscriber Subcriber to flow message.
protected booluseGlobalCurrent Flag to use the global current velocity or the individually assigned current velocity.
protected std::map< std::string, gazebo::transport::PublisherPtr >hydroPub Publishers of hydrodynamic and hydrostatic forces and torques in the case the debug flag is on.
protected virtual voidConnect() Connects the update event callback.
protected voidUpdateFlowVelocity(ConstVector3dPtr & _msg) Reads flow velocity topic.
protected virtual voidPublishCurrentVelocityMarker() Publish current velocity marker.
protected virtual voidPublishIsSubmerged() Publishes the state of the vehicle (is submerged)
protected virtual voidPublishRestoringForce(gazebo::physics::LinkPtr _link) Publish restoring force.
protected virtual voidPublishHydrodynamicWrenches(gazebo::physics::LinkPtr _link) Publish hydrodynamic wrenches.
protected virtual voidGenWrenchMsg(ignition::math::Vector3d _force,ignition::math::Vector3d _torque,gazebo::msgs::WrenchStamped & _output) Returns the wrench message for debugging topics.
protected virtual voidInitDebug(gazebo::physics::LinkPtr _link,gazebo::HydrodynamicModelPtr_hydro) Sets the topics used for publishing the intermediate data during the simulation.
Members
publicUnderwaterObjectPlugin()

Constructor.

public virtual~UnderwaterObjectPlugin()

Destructor.

public virtual voidLoad(gazebo::physics::ModelPtr _model,sdf::ElementPtr _sdf)
public virtual voidInit()
public virtual voidUpdate(const gazebo::common::UpdateInfo & _info)

Update the simulation state.

Parameters
  • _info Information used in the update event.
protected std::map< gazebo::physics::LinkPtr,HydrodynamicModelPtr>models

Pairs of links & corresponding hydrodynamic models.

protected ignition::math::Vector3dflowVelocity

Flow velocity vector read from topic.

protected gazebo::event::ConnectionPtrupdateConnection

Update event.

protected gazebo::physics::WorldPtrworld

Pointer to the world plugin.

protected gazebo::physics::ModelPtrmodel

Pointer to the model structure.

protected gazebo::transport::NodePtrnode

Gazebo node.

protected std::stringbaseLinkName

Name of vehicle's base_link.

protected gazebo::transport::SubscriberPtrflowSubscriber

Subcriber to flow message.

protected booluseGlobalCurrent

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

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

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

protected virtual voidConnect()

Connects the update event callback.

protected voidUpdateFlowVelocity(ConstVector3dPtr & _msg)

Reads flow velocity topic.

protected virtual voidPublishCurrentVelocityMarker()

Publish current velocity marker.

protected virtual voidPublishIsSubmerged()

Publishes the state of the vehicle (is submerged)

Publish restoring force.

Parameters
  • _link Pointer to the link where the force information will be extracted from

Publish hydrodynamic wrenches.

Parameters
  • _link Pointer to the link where the force information will be extracted from
protected virtual voidGenWrenchMsg(ignition::math::Vector3d _force,ignition::math::Vector3d _torque,gazebo::msgs::WrenchStamped & _output)

Returns the wrench message for debugging topics.

Parameters
  • _force Force vector

  • _torque Torque vector

  • _output Stamped wrench message to be updated

protected virtual voidInitDebug(gazebo::physics::LinkPtr _link,gazebo::HydrodynamicModelPtr_hydro)

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

Parameters
  • _link Pointer to the link

  • _hydro Pointer to the hydrodynamic model