18 #ifndef USV_GAZEBO_PLUGINS_DYNAMICS_PLUGIN_HH_ 19 #define USV_GAZEBO_PLUGINS_DYNAMICS_PLUGIN_HH_ 25 #include <gazebo/common/common.hh> 26 #include <ignition/math/Vector3.hh> 27 #include <gazebo/physics/physics.hh> 61 class UsvDynamicsPlugin :
public ModelPlugin
64 public: UsvDynamicsPlugin();
67 public:
virtual ~UsvDynamicsPlugin() =
default;
70 public:
virtual void Load(physics::ModelPtr _model,
71 sdf::ElementPtr _sdf);
74 protected:
virtual void Update();
82 private:
double SdfParamDouble(sdf::ElementPtr _sdfPtr,
83 const std::string &_paramName,
84 const double _defaultVal)
const;
90 private:
double CircleSegment(
double R,
double h);
93 private: physics::WorldPtr world;
98 private: physics::LinkPtr link;
101 private: common::Time prevUpdateTime;
105 private: ignition::math::Vector3d prevLinVel;
109 private: ignition::math::Vector3d prevAngVel;
113 private:
double paramXdotU;
116 private:
double paramYdotV;
119 private:
double paramNdotR;
122 private:
double paramXu;
125 private:
double paramXuu;
128 private:
double paramYv;
131 private:
double paramYvv;
134 private:
double paramZw;
137 private:
double paramKp;
140 private:
double paramMq;
143 private:
double paramNr;
146 private:
double paramNrr;
149 private:
double waterLevel;
152 private:
double waterDensity;
155 private:
double paramBoatLength;
158 private:
double paramBoatWidth;
161 private:
double paramHullRadius;
164 private:
int paramLengthN;
167 private: Eigen::MatrixXd Ma;
170 protected: std::string waveModelName;
185 private: event::ConnectionPtr updateConnection;
188 private: std::shared_ptr<const asv::WaveParameters> waveParams;