19 #ifndef __UUV_GAZEBO_PLUGINS_UMBILICAL_PLUGIN_HH__ 20 #define __UUV_GAZEBO_PLUGINS_UMBILICAL_PLUGIN_HH__ 25 #include <gazebo/gazebo.hh> 26 #include <gazebo/common/UpdateInfo.hh> 27 #include <gazebo/common/Plugin.hh> 28 #include <gazebo/physics/World.hh> 29 #include <gazebo/transport/TransportTypes.hh> 41 const std::string& _fromLink,
42 const ignition::math::Pose3d& _fromPose,
43 const ignition::math::Pose3d& _toPose,
44 physics::ModelPtr _model);
69 protected:
virtual void Load(physics::ModelPtr _model, sdf::ElementPtr _sdf);
72 protected:
virtual void OnUpdate(
const common::UpdateInfo&);
75 protected:
void UpdateFlowVelocity(ConstVector3dPtr &_msg);
81 protected: gazebo::physics::ModelPtr
model;
84 protected: gazebo::physics::WorldPtr
world;
87 protected: gazebo::transport::NodePtr
node;
96 protected: std::shared_ptr<UmbilicalModel>
umbilical;
gazebo::physics::ModelPtr model
Pointer to the model structure.
gazebo::transport::SubscriberPtr flowSubscriber
Subcriber to flow message.
std::shared_ptr< UmbilicalSegment > prev
std::shared_ptr< UmbilicalModel > umbilical
Pointer to UmbilicalModel used in this plugin.
gazebo::transport::NodePtr node
Gazebo node.
std::shared_ptr< UmbilicalSegment > next
event::ConnectionPtr updateConnection
Pointer to the update event connection.
Various umbilical models.
static sdf::SDFPtr sdfSegment
boost::shared_ptr< UmbilicalSegment > UmbilicalSegmentPtr
ignition::math::Vector3d flowVelocity
Flow velocity vector read from topic.
gazebo::physics::WorldPtr world
Pointer to the world plugin.