ThrusterPlugin.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_THRUSTER_PLUGIN_HH__
20 #define __UUV_GAZEBO_PLUGINS_THRUSTER_PLUGIN_HH__
21 
22 #include <boost/scoped_ptr.hpp>
23 
24 #include <map>
25 #include <string>
26 #include <memory>
27 
28 #include <gazebo/gazebo.hh>
29 #include <gazebo/transport/TransportTypes.hh>
30 
31 #include <sdf/sdf.hh>
32 
35 
36 #include "Double.pb.h"
37 
38 namespace gazebo
39 {
41 typedef const boost::shared_ptr<const uuv_gazebo_plugins_msgs::msgs::Double>
43 
45 class ThrusterPlugin : public ModelPlugin
46 {
48  public: ThrusterPlugin();
49 
51  public: virtual ~ThrusterPlugin();
52 
53  // Documentation inherited.
54  public: virtual void Load(physics::ModelPtr _model,
55  sdf::ElementPtr _sdf);
56 
57  // Documentation inherited.
58  public: virtual void Init();
59 
61  public: virtual void Reset();
62 
65  public: void Update(const common::UpdateInfo &_info);
66 
68  protected: void UpdateInput(ConstDoublePtr &_msg);
69 
71  protected: std::shared_ptr<Dynamics> thrusterDynamics;
72 
74  protected: std::shared_ptr<ConversionFunction> conversionFunction;
75 
77  protected: event::ConnectionPtr updateConnection;
78 
80  protected: physics::LinkPtr thrusterLink;
81 
83  protected: transport::NodePtr node;
84 
86  protected: transport::SubscriberPtr commandSubscriber;
87 
89  protected: transport::PublisherPtr thrustTopicPublisher;
90 
93  protected: double inputCommand;
94 
96  protected: double thrustForce;
97 
99  protected: common::Time thrustForceStamp;
100 
102  protected: physics::JointPtr joint;
103 
105  protected: double clampMin;
106 
108  protected: double clampMax;
109 
111  protected: double thrustMin;
112 
114  protected: double thrustMax;
115 
117  protected: int thrusterID;
118 
120  protected: std::string topicPrefix;
121 
123  protected: double gain;
124 
126  protected: bool isOn;
127 
129  protected: double thrustEfficiency;
130 
132  protected: double propellerEfficiency;
133 
135  protected: ignition::math::Vector3d thrusterAxis;
136 };
137 }
138 #endif // __UUV_GAZEBO_PLUGINS_THRUSTER_PLUGIN_HH__
void Update(const common::UpdateInfo &_info)
Update the simulation state.
virtual ~ThrusterPlugin()
Destructor.
double clampMax
: Optional: Commands greater than this value will be clamped.
physics::LinkPtr thrusterLink
Pointer to the thruster link.
physics::JointPtr joint
Optional: The rotor joint, used for visualization.
1D dynamic models
bool isOn
Optional: Flag to indicate if the thruster is turned on or off.
double propellerEfficiency
Optional: Propeller angular velocity efficiency term.
transport::PublisherPtr thrustTopicPublisher
Publisher to the output thrust topic.
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
std::shared_ptr< ConversionFunction > conversionFunction
Thruster conversion function.
common::Time thrustForceStamp
Time stamp of latest thrust force.
double clampMin
: Optional: Commands less than this value will be clamped.
double inputCommand
Input command, typically desired angular velocity of the rotor.
std::shared_ptr< Dynamics > thrusterDynamics
Thruster dynamic model.
virtual void Reset()
Custom plugin reset behavior.
double thrustMax
: Optional: Maximum thrust force output
transport::SubscriberPtr commandSubscriber
Subscriber to the reference signal topic.
transport::NodePtr node
Gazebo node.
double thrustMin
: Optional: Minimum thrust force output
Description of the conversion function fo a thruster.
int thrusterID
Thruster ID, used to generated topic names automatically.
double thrustEfficiency
Optional: Output thrust efficiency factor of the thruster.
Class for the thruster plugin.
ignition::math::Vector3d thrusterAxis
The axis about which the thruster rotates.
double gain
: Optional: Gain factor: Desired angular velocity = command * gain
void UpdateInput(ConstDoublePtr &_msg)
Callback for the input topic subscriber.
virtual void Load(physics::ModelPtr _model, sdf::ElementPtr _sdf)
event::ConnectionPtr updateConnection
Update event.
std::string topicPrefix
Thruster topics prefix.
ThrusterPlugin()
Constructor.
double thrustForce
Latest thrust force in [N].


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