20 #ifndef __UUV_GAZEBO_PLUGINS_UNDERWATER_OBJECT_HH__ 21 #define __UUV_GAZEBO_PLUGINS_UNDERWATER_OBJECT_HH__ 26 #include <gazebo/gazebo.hh> 27 #include <gazebo/msgs/msgs.hh> 44 public:
virtual void Load(gazebo::physics::ModelPtr _model,
45 sdf::ElementPtr _sdf);
48 public:
virtual void Init();
52 public:
virtual void Update(
const gazebo::common::UpdateInfo &_info);
55 protected:
virtual void Connect();
70 gazebo::physics::LinkPtr _link);
76 gazebo::physics::LinkPtr _link);
83 ignition::math::Vector3d _force, ignition::math::Vector3d _torque,
84 gazebo::msgs::WrenchStamped &_output);
90 protected:
virtual void InitDebug(gazebo::physics::LinkPtr _link,
94 protected: std::map<gazebo::physics::LinkPtr,
104 protected: gazebo::physics::WorldPtr
world;
107 protected: gazebo::physics::ModelPtr
model;
110 protected: gazebo::transport::NodePtr
node;
124 protected: std::map<std::string, gazebo::transport::PublisherPtr>
hydroPub;
128 #endif // __UUV_GAZEBO_PLUGINS_UNDERWATER_OBJECT_HH__ std::map< gazebo::physics::LinkPtr, HydrodynamicModelPtr > models
Pairs of links & corresponding hydrodynamic models.
gazebo::event::ConnectionPtr updateConnection
Update event.
std::map< std::string, gazebo::transport::PublisherPtr > hydroPub
Publishers of hydrodynamic and hydrostatic forces and torques in the case the debug flag is on...
virtual void PublishHydrodynamicWrenches(gazebo::physics::LinkPtr _link)
Publish hydrodynamic wrenches.
virtual void PublishIsSubmerged()
Publishes the state of the vehicle (is submerged)
virtual void PublishRestoringForce(gazebo::physics::LinkPtr _link)
Publish restoring force.
void UpdateFlowVelocity(ConstVector3dPtr &_msg)
Reads flow velocity topic.
gazebo::physics::WorldPtr world
Pointer to the world plugin.
virtual void Connect()
Connects the update event callback.
Gazebo model plugin class for underwater objects.
gazebo::transport::NodePtr node
Gazebo node.
ignition::math::Vector3d flowVelocity
Flow velocity vector read from topic.
virtual ~UnderwaterObjectPlugin()
Destructor.
bool useGlobalCurrent
Flag to use the global current velocity or the individually assigned current velocity.
virtual void InitDebug(gazebo::physics::LinkPtr _link, gazebo::HydrodynamicModelPtr _hydro)
Sets the topics used for publishing the intermediate data during the simulation.
std::string baseLinkName
Name of vehicle's base_link.
virtual void Update(const gazebo::common::UpdateInfo &_info)
Update the simulation state.
This file contains the definition for different classes of hydrodynamic models for submerged objects...
UnderwaterObjectPlugin()
Constructor.
virtual void PublishCurrentVelocityMarker()
Publish current velocity marker.
virtual void GenWrenchMsg(ignition::math::Vector3d _force, ignition::math::Vector3d _torque, gazebo::msgs::WrenchStamped &_output)
Returns the wrench message for debugging topics.
gazebo::physics::ModelPtr model
Pointer to the model structure.
boost::shared_ptr< HydrodynamicModel > HydrodynamicModelPtr
Pointer to model.
gazebo::transport::SubscriberPtr flowSubscriber
Subcriber to flow message.
virtual void Load(gazebo::physics::ModelPtr _model, sdf::ElementPtr _sdf)