UnderwaterObjectPlugin
class gazebo::UnderwaterObjectPlugin
¶
class gazebo::UnderwaterObjectPlugin : public ModelPlugin
Gazebo model plugin class for underwater objects.
Summary¶
Members | Descriptions |
---|---|
public UnderwaterObjectPlugin () |
Constructor. |
public virtual ~UnderwaterObjectPlugin () |
Destructor. |
public virtual void Load (gazebo::physics::ModelPtr _model,sdf::ElementPtr _sdf) |
|
public virtual void Init () |
|
public virtual void Update (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::Vector3d flowVelocity |
Flow velocity vector read from topic. |
protected gazebo::event::ConnectionPtr updateConnection |
Update event. |
protected gazebo::physics::WorldPtr world |
Pointer to the world plugin. |
protected gazebo::physics::ModelPtr model |
Pointer to the model structure. |
protected gazebo::transport::NodePtr node |
Gazebo node. |
protected std::string baseLinkName |
Name of vehicle's base_link. |
protected gazebo::transport::SubscriberPtr flowSubscriber |
Subcriber to flow message. |
protected bool useGlobalCurrent |
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 void Connect () |
Connects the update event callback. |
protected void UpdateFlowVelocity (ConstVector3dPtr & _msg) |
Reads flow velocity topic. |
protected virtual void PublishCurrentVelocityMarker () |
Publish current velocity marker. |
protected virtual void PublishIsSubmerged () |
Publishes the state of the vehicle (is submerged) |
protected virtual void PublishRestoringForce (gazebo::physics::LinkPtr _link) |
Publish restoring force. |
protected virtual void PublishHydrodynamicWrenches (gazebo::physics::LinkPtr _link) |
Publish hydrodynamic wrenches. |
protected virtual void GenWrenchMsg (ignition::math::Vector3d _force,ignition::math::Vector3d _torque,gazebo::msgs::WrenchStamped & _output) |
Returns the wrench message for debugging topics. |
protected virtual void InitDebug (gazebo::physics::LinkPtr _link, gazebo::HydrodynamicModelPtr _hydro) |
Sets the topics used for publishing the intermediate data during the simulation. |
Members¶
public
UnderwaterObjectPlugin
()
¶
Constructor.
public virtual
~UnderwaterObjectPlugin
()
¶
Destructor.
public virtual void
Load
(gazebo::physics::ModelPtr _model,sdf::ElementPtr _sdf)
¶
public virtual void
Init
()
¶
public virtual void
Update
(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::Vector3d
flowVelocity
¶
Flow velocity vector read from topic.
protected gazebo::event::ConnectionPtr
updateConnection
¶
Update event.
protected gazebo::physics::WorldPtr
world
¶
Pointer to the world plugin.
protected gazebo::physics::ModelPtr
model
¶
Pointer to the model structure.
protected gazebo::transport::NodePtr
node
¶
Gazebo node.
protected std::string
baseLinkName
¶
Name of vehicle's base_link.
protected gazebo::transport::SubscriberPtr
flowSubscriber
¶
Subcriber to flow message.
protected bool
useGlobalCurrent
¶
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 void
Connect
()
¶
Connects the update event callback.
protected void
UpdateFlowVelocity
(ConstVector3dPtr & _msg)
¶
Reads flow velocity topic.
protected virtual void
PublishCurrentVelocityMarker
()
¶
Publish current velocity marker.
protected virtual void
PublishIsSubmerged
()
¶
Publishes the state of the vehicle (is submerged)
protected virtual void
PublishRestoringForce
(gazebo::physics::LinkPtr _link)
¶
Publish restoring force.
Parameters¶
_link
Pointer to the link where the force information will be extracted from
protected virtual void
PublishHydrodynamicWrenches
(gazebo::physics::LinkPtr _link)
¶
Publish hydrodynamic wrenches.
Parameters¶
_link
Pointer to the link where the force information will be extracted from
protected virtual void
GenWrenchMsg
(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 void
InitDebug
(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