usv_gazebo_thrust_plugin.hh
Go to the documentation of this file.
1 /*
2  * Copyright (C) 2017 Brian Bingham
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  *
16 */
17 
18 #ifndef USV_GAZEBO_PLUGINS_THRUST_HH
19 #define USV_GAZEBO_PLUGINS_THRUST_HH
20 
21 #include <ros/ros.h>
22 #include <std_msgs/Float32.h>
23 #include <sensor_msgs/JointState.h>
24 #include <memory>
25 #include <mutex>
26 #include <string>
27 #include <vector>
28 #include <gazebo/common/CommonTypes.hh>
29 #include <gazebo/common/Plugin.hh>
30 #include <gazebo/common/Time.hh>
31 #include <gazebo/physics/physics.hh>
32 #include <sdf/sdf.hh>
33 
34 namespace gazebo
35 {
36  // Foward declaration of UsvThrust class
37  class UsvThrust;
38 
40  class Thruster
41  {
44  public: explicit Thruster(UsvThrust *_parent);
45 
48  public: void OnThrustCmd(const std_msgs::Float32::ConstPtr &_msg);
49 
52  public: void OnThrustAngle(const std_msgs::Float32::ConstPtr &_msg);
53 
55  public: double maxCmd;
56 
58  public: double maxForceFwd;
59 
61  public: double maxForceRev;
62 
64  public: double maxAngle;
65 
67  public: physics::LinkPtr link;
68 
70  public: int mappingType;
71 
73  public: std::string cmdTopic;
74 
77 
80  public: bool enableAngle;
81 
83  public: std::string angleTopic;
84 
87 
89  public: double currCmd;
90 
92  public: double desiredAngle;
93 
95  public: common::Time lastCmdTime;
96 
98  public: common::Time lastAngleUpdateTime;
99 
101  public: physics::JointPtr propJoint;
102 
104  public: physics::JointPtr engineJoint;
105 
107  public: common::PID engineJointPID;
108 
110  protected: UsvThrust *plugin;
111  };
112 
180 
181  class UsvThrust : public ModelPlugin
182  {
184  public: UsvThrust() = default;
185 
187  public: virtual ~UsvThrust() = default;
188 
189  // Documentation inherited.
190  public: virtual void Load(physics::ModelPtr _parent,
191  sdf::ElementPtr _sdf);
192 
194  protected: virtual void Update();
195 
202  private: double SdfParamDouble(sdf::ElementPtr _sdfPtr,
203  const std::string &_paramName,
204  const double _defaultVal) const;
205 
209  private: double ScaleThrustCmd(const double _cmd,
210  const double _max_cmd,
211  const double _max_pos,
212  const double _max_neg) const;
213 
224  private: double Glf(const double _x,
225  const float _A,
226  const float _K,
227  const float _B,
228  const float _v,
229  const float _C,
230  const float _M) const;
231 
236  private: double GlfThrustCmd(const double _cmd,
237  const double _maxPos,
238  const double _maxNeg) const;
239 
243  private: void RotateEngine(size_t _i,
244  common::Time _stepTime);
245 
248  private: void SpinPropeller(size_t _i);
249 
252  public: std::mutex mutex;
253 
255  private: std::unique_ptr<ros::NodeHandle> rosnode;
256 
258  public: physics::WorldPtr world;
259 
262  private: physics::ModelPtr model;
263 
265  private: double cmdTimeout;
266 
268  private: std::vector<Thruster> thrusters;
269 
271  private: event::ConnectionPtr updateConnection;
272 
275 
277  private: sensor_msgs::JointState jointStateMsg;
278  };
279 }
280 
281 #endif
double desiredAngle
Most recent desired angle.
physics::WorldPtr world
Pointer to the Gazebo world, retrieved when the model is loaded.
void OnThrustCmd(const std_msgs::Float32::ConstPtr &_msg)
Callback for new thrust commands.
A plugin to simulate a propulsion system under water. This plugin accepts the following SDF parameter...
physics::JointPtr propJoint
Joint controlling the propeller.
physics::LinkPtr link
Link where thrust force is applied.
void OnThrustAngle(const std_msgs::Float32::ConstPtr &_msg)
Callback for new thrust angle commands.
std::vector< Thruster > thrusters
Vector of thruster instances.
double maxForceFwd
Max forward force in Newtons.
ros::Subscriber angleSub
Subscription to thruster commands.
double maxForceRev
Max reverse force in Newtons.
common::PID engineJointPID
PID for engine joint angle.
Thruster(UsvThrust *_parent)
Constructor.
std::unique_ptr< ros::NodeHandle > rosnode
The ROS node handler used for communications.
common::Time lastCmdTime
Last time received a command via ROS topic.
event::ConnectionPtr updateConnection
Pointer to the update event connection.
UsvThrust * plugin
Plugin parent pointer - for accessing world, etc.
sensor_msgs::JointState jointStateMsg
The propeller message state.
common::Time lastAngleUpdateTime
Last time of update.
double cmdTimeout
Timeout for receiving Drive commands [s].
std::mutex mutex
A mutex to protect member variables accessed during OnThustCmd() and Update().
bool enableAngle
If true, thruster will have adjustable angle. If false, thruster will have constant angle...
ros::Subscriber cmdSub
Subscription to thruster commands.
int mappingType
Thruster mapping (0=linear; 1=GLF, nonlinear).
double maxCmd
Maximum abs val of incoming command.
std::string cmdTopic
Topic name for incoming ROS thruster commands.
physics::ModelPtr model
Pointer to Gazebo parent model, retrieved when the model is loaded.
std::string angleTopic
Topic name for incoming ROS thruster angle commands.
double maxAngle
Maximum abs val of angle.
physics::JointPtr engineJoint
Joint controlling the engine.
double currCmd
Current, most recent command.
ros::Publisher jointStatePub
For publishing to /joint_state with propeller state.


usv_gazebo_plugins
Author(s): Brian Bingham , Carlos Aguero
autogenerated on Thu May 7 2020 03:54:47