FinPlugin.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 
18 
19 #ifndef __UUV_GAZEBO_PLUGINS_FIN_PLUGIN_HH__
20 #define __UUV_GAZEBO_PLUGINS_FIN_PLUGIN_HH__
21 
22 #include <boost/scoped_ptr.hpp>
23 #include <gazebo/gazebo.hh>
24 #include <sdf/sdf.hh>
25 
26 #include <gazebo/msgs/msgs.hh>
29 
30 #include "Double.pb.h"
31 
32 namespace gazebo {
33 
35 typedef const boost::shared_ptr<const uuv_gazebo_plugins_msgs::msgs::Double>
37 
38 class FinPlugin : public ModelPlugin
39 {
41  public: FinPlugin();
42 
44  public: virtual ~FinPlugin();
45 
46  // Documentation inherited.
47  public: virtual void Load(physics::ModelPtr _model,
48  sdf::ElementPtr _sdf);
49 
50  // Documentation inherited.
51  public: virtual void Init();
52 
55  public: void OnUpdate(const common::UpdateInfo &_info);
56 
58  protected: void UpdateInput(ConstDoublePtr &_msg);
59 
61  protected: void UpdateCurrentVelocity(ConstVector3dPtr &_msg);
62 
64  protected: std::shared_ptr<Dynamics> dynamics;
65 
67  protected: std::shared_ptr<LiftDrag> liftdrag;
68 
70  protected: event::ConnectionPtr updateConnection;
71 
73  protected: transport::NodePtr node;
74 
76  protected: physics::JointPtr joint;
77 
79  protected: physics::LinkPtr link;
80 
82  protected: transport::SubscriberPtr commandSubscriber;
83 
85  protected: transport::PublisherPtr anglePublisher;
86 
88  protected: ignition::math::Vector3d finForce;
89 
91  protected: double inputCommand;
92 
94  protected: int finID;
95 
97  protected: std::string topicPrefix;
98 
100  protected: double angle;
101 
103  protected: common::Time angleStamp;
104 
106  protected: transport::SubscriberPtr currentSubscriber;
107 
109  protected: ignition::math::Vector3d currentVelocity;
110 };
111 }
112 
113 #endif
transport::SubscriberPtr currentSubscriber
Subcriber to current message.
Definition: FinPlugin.hh:106
ignition::math::Vector3d finForce
Force component calculated from the lift and drag module.
Definition: FinPlugin.hh:88
1D dynamic models
double angle
Latest fin angle in [rad].
Definition: FinPlugin.hh:100
virtual void Load(physics::ModelPtr _model, sdf::ElementPtr _sdf)
Definition: FinPlugin.cc:48
double inputCommand
Latest input command.
Definition: FinPlugin.hh:91
const boost::shared_ptr< const uuv_gazebo_plugins_msgs::msgs::Double > ConstDoublePtr
Definition of a pointer to the floating point message.
Definition: FinPlugin.hh:36
physics::JointPtr joint
The fin joint.
Definition: FinPlugin.hh:76
ignition::math::Vector3d currentVelocity
Current velocity vector read from topic.
Definition: FinPlugin.hh:109
void OnUpdate(const common::UpdateInfo &_info)
Update the simulation state.
Definition: FinPlugin.cc:137
virtual ~FinPlugin()
Destructor.
Definition: FinPlugin.cc:35
Various Lift&Drag models for Fins.
common::Time angleStamp
Time stamp of latest thrust force.
Definition: FinPlugin.hh:103
virtual void Init()
Definition: FinPlugin.cc:132
void UpdateCurrentVelocity(ConstVector3dPtr &_msg)
Reads current velocity topic.
Definition: FinPlugin.cc:195
std::shared_ptr< Dynamics > dynamics
Fin dynamic model.
Definition: FinPlugin.hh:64
void UpdateInput(ConstDoublePtr &_msg)
Callback for the input topic subscriber.
Definition: FinPlugin.cc:189
FinPlugin()
Constructor.
Definition: FinPlugin.cc:30
transport::NodePtr node
Gazebo node.
Definition: FinPlugin.hh:73
std::string topicPrefix
Topic prefix.
Definition: FinPlugin.hh:97
physics::LinkPtr link
The fin link.
Definition: FinPlugin.hh:79
int finID
Fin ID.
Definition: FinPlugin.hh:94
transport::SubscriberPtr commandSubscriber
Subscriber to the reference signal topic.
Definition: FinPlugin.hh:82
event::ConnectionPtr updateConnection
Update event.
Definition: FinPlugin.hh:70
transport::PublisherPtr anglePublisher
Publisher to the output thrust topic.
Definition: FinPlugin.hh:85
std::shared_ptr< LiftDrag > liftdrag
Lift&Drag model.
Definition: FinPlugin.hh:67


uuv_gazebo_plugins
Author(s): Musa Morena Marcusso Manhaes , Sebastian Scherer , Luiz Ricardo Douat
autogenerated on Mon Jul 1 2019 19:39:12