18 #ifndef USV_GAZEBO_PLUGINS_THRUST_HH 19 #define USV_GAZEBO_PLUGINS_THRUST_HH 22 #include <std_msgs/Float32.h> 23 #include <sensor_msgs/JointState.h> 28 #include <gazebo/common/CommonTypes.hh> 29 #include <gazebo/common/Plugin.hh> 30 #include <gazebo/common/Time.hh> 31 #include <gazebo/physics/physics.hh> 48 public:
void OnThrustCmd(
const std_msgs::Float32::ConstPtr &_msg);
52 public:
void OnThrustAngle(
const std_msgs::Float32::ConstPtr &_msg);
67 public: physics::LinkPtr
link;
190 public:
virtual void Load(physics::ModelPtr _parent,
191 sdf::ElementPtr _sdf);
194 protected:
virtual void Update();
202 private:
double SdfParamDouble(sdf::ElementPtr _sdfPtr,
203 const std::string &_paramName,
204 const double _defaultVal)
const;
209 private:
double ScaleThrustCmd(
const double _cmd,
210 const double _max_cmd,
211 const double _max_pos,
212 const double _max_neg)
const;
224 private:
double Glf(
const double _x,
230 const float _M)
const;
236 private:
double GlfThrustCmd(
const double _cmd,
237 const double _maxPos,
238 const double _maxNeg)
const;
243 private:
void RotateEngine(
size_t _i,
244 common::Time _stepTime);
248 private:
void SpinPropeller(
size_t _i);
255 private: std::unique_ptr<ros::NodeHandle>
rosnode;
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.