UnderwaterObjectPlugin.hh
Go to the documentation of this file.
1 // Copyright (c) 2016 The UUV Simulator Authors.
2 // All rights reserved.
3 //
4 // Licensed under the Apache License, Version 2.0 (the "License");
5 // you may not use this file except in compliance with the License.
6 // You may obtain a copy of the License at
7 //
8 // http://www.apache.org/licenses/LICENSE-2.0
9 //
10 // Unless required by applicable law or agreed to in writing, software
11 // distributed under the License is distributed on an "AS IS" BASIS,
12 // WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
13 // See the License for the specific language governing permissions and
14 // limitations under the License.
15 
19 
20 #ifndef __UUV_GAZEBO_PLUGINS_UNDERWATER_OBJECT_HH__
21 #define __UUV_GAZEBO_PLUGINS_UNDERWATER_OBJECT_HH__
22 
23 #include <map>
24 #include <string>
25 
26 #include <gazebo/gazebo.hh>
27 #include <gazebo/msgs/msgs.hh>
28 
31 
32 namespace gazebo
33 {
35 class UnderwaterObjectPlugin : public gazebo::ModelPlugin
36 {
38  public: UnderwaterObjectPlugin();
39 
41  public: virtual ~UnderwaterObjectPlugin();
42 
43  // Documentation inherited.
44  public: virtual void Load(gazebo::physics::ModelPtr _model,
45  sdf::ElementPtr _sdf);
46 
47  // Documentation inherited.
48  public: virtual void Init();
49 
52  public: virtual void Update(const gazebo::common::UpdateInfo &_info);
53 
55  protected: virtual void Connect();
56 
58  protected: void UpdateFlowVelocity(ConstVector3dPtr &_msg);
59 
61  protected: virtual void PublishCurrentVelocityMarker();
62 
64  protected: virtual void PublishIsSubmerged();
65 
69  protected: virtual void PublishRestoringForce(
70  gazebo::physics::LinkPtr _link);
71 
75  protected: virtual void PublishHydrodynamicWrenches(
76  gazebo::physics::LinkPtr _link);
77 
82  protected: virtual void GenWrenchMsg(
83  ignition::math::Vector3d _force, ignition::math::Vector3d _torque,
84  gazebo::msgs::WrenchStamped &_output);
85 
90  protected: virtual void InitDebug(gazebo::physics::LinkPtr _link,
92 
94  protected: std::map<gazebo::physics::LinkPtr,
96 
98  protected: ignition::math::Vector3d flowVelocity;
99 
101  protected: gazebo::event::ConnectionPtr updateConnection;
102 
104  protected: gazebo::physics::WorldPtr world;
105 
107  protected: gazebo::physics::ModelPtr model;
108 
110  protected: gazebo::transport::NodePtr node;
111 
113  protected: std::string baseLinkName;
114 
116  protected: gazebo::transport::SubscriberPtr flowSubscriber;
117 
120  protected: bool useGlobalCurrent;
121 
124  protected: std::map<std::string, gazebo::transport::PublisherPtr> hydroPub;
125 };
126 }
127 
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&#39;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...
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.
General definitions.
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)


uuv_gazebo_plugins
Author(s): Musa Morena Marcusso Manhaes , Sebastian Scherer , Luiz Ricardo Douat
autogenerated on Thu Jun 18 2020 03:28:24