26 #include <ignition/math/Pose3.hh> 36 UsvDynamicsPlugin::UsvDynamicsPlugin()
41 double UsvDynamicsPlugin::SdfParamDouble(sdf::ElementPtr _sdfPtr,
42 const std::string &_paramName,
const double _defaultVal)
const 44 if (!_sdfPtr->HasElement(_paramName))
47 "Using default value of <" << _defaultVal <<
">.");
51 double val = _sdfPtr->Get<
double>(_paramName);
53 "> to <" << val <<
">.");
58 void UsvDynamicsPlugin::Load(physics::ModelPtr _model, sdf::ElementPtr _sdf)
60 ROS_DEBUG(
"Loading usv_gazebo_dynamics_plugin");
61 this->world = _model->GetWorld();
65 if (!_sdf->HasElement(
"bodyName") ||
66 !_sdf->GetElement(
"bodyName")->GetValue())
68 this->link = _model->GetLink();
69 linkName = this->link->GetName();
74 linkName = _sdf->GetElement(
"bodyName")->Get<std::string>();
75 this->link = _model->GetLink(linkName);
81 ROS_FATAL(
"usv_gazebo_dynamics_plugin error: bodyName: %s does not exist\n",
90 this->waterLevel = this->SdfParamDouble(_sdf,
"waterLevel" , 0.5);
91 this->waterDensity = this->SdfParamDouble(_sdf,
"waterDensity", 997.7735);
92 this->paramXdotU = this->SdfParamDouble(_sdf,
"xDotU" , 5);
93 this->paramYdotV = this->SdfParamDouble(_sdf,
"yDotV" , 5);
94 this->paramNdotR = this->SdfParamDouble(_sdf,
"nDotR" , 1);
95 this->paramXu = this->SdfParamDouble(_sdf,
"xU" , 20);
96 this->paramXuu = this->SdfParamDouble(_sdf,
"xUU" , 0);
97 this->paramYv = this->SdfParamDouble(_sdf,
"yV" , 20);
98 this->paramYvv = this->SdfParamDouble(_sdf,
"yVV" , 0);
99 this->paramZw = this->SdfParamDouble(_sdf,
"zW" , 20);
100 this->paramKp = this->SdfParamDouble(_sdf,
"kP" , 20);
101 this->paramMq = this->SdfParamDouble(_sdf,
"mQ" , 20);
102 this->paramNr = this->SdfParamDouble(_sdf,
"nR" , 20);
103 this->paramNrr = this->SdfParamDouble(_sdf,
"nRR" , 0);
104 this->paramHullRadius = this->SdfParamDouble(_sdf,
"hullRadius" , 0.213);
105 this->paramBoatWidth = this->SdfParamDouble(_sdf,
"boatWidth" , 1.0);
106 this->paramBoatLength = this->SdfParamDouble(_sdf,
"boatLength" , 1.35);
108 if (!_sdf->HasElement(
"length_n"))
112 "Using default value of <" << defaultVal <<
">.");
113 this->paramLengthN = defaultVal;
117 this->paramLengthN = _sdf->GetElement(
"length_n")->Get<
int>();
122 if (_sdf->HasElement(
"wave_model"))
124 this->waveModelName = _sdf->Get<std::string>(
"wave_model");
126 this->waveParams =
nullptr;
129 #if GAZEBO_MAJOR_VERSION >= 8 130 const ignition::math::Vector3d kInertia =
131 this->link->GetInertial()->PrincipalMoments();
132 const double kMass = this->link->GetInertial()->Mass();
134 const ignition::math::Vector3d kInertia =
135 this->link->GetInertial()->GetPrincipalMoments().Ign();
136 const double kMass = this->link->GetInertial()->GetMass();
140 ROS_DEBUG(
"USV Dynamics Parameters: From URDF XACRO model definition");
143 " Y:" << kInertia[1] <<
" Z:" << kInertia[2]);
146 #if GAZEBO_MAJOR_VERSION >= 8 147 this->prevUpdateTime = this->world->SimTime();
149 this->prevUpdateTime = this->world->GetSimTime();
153 this->updateConnection = event::Events::ConnectWorldUpdateBegin(
154 std::bind(&UsvDynamicsPlugin::Update,
this));
157 this->Ma = Eigen::MatrixXd(6, 6);
159 this->paramXdotU, 0, 0, 0, 0, 0,
160 0, this->paramYdotV, 0, 0, 0, 0,
164 0, 0, 0, 0, 0, this->paramNdotR;
167 double UsvDynamicsPlugin::CircleSegment(
double R,
double h)
169 return R*R*acos( (R-h)/R ) - (R-h)*sqrt(2*R*h-h*h);
173 void UsvDynamicsPlugin::Update()
176 if (waveParams ==
nullptr)
178 gzmsg <<
"usv_gazebo_dynamics_plugin: waveParams is null. " 179 <<
" Trying to get wave parameters from ocean model" << std::endl;
181 this->world, this->waveModelName);
184 #if GAZEBO_MAJOR_VERSION >= 8 185 const common::Time kTimeNow = this->world->SimTime();
187 const common::Time kTimeNow = this->world->GetSimTime();
189 double dt = (kTimeNow - this->prevUpdateTime).Double();
190 this->prevUpdateTime = kTimeNow;
193 #if GAZEBO_MAJOR_VERSION >= 8 194 const ignition::math::Pose3d kPose = this->link->WorldPose();
196 const ignition::math::Pose3d kPose = this->link->GetWorldPose().Ign();
198 const ignition::math::Vector3d kEuler = kPose.Rot().Euler();
201 #if GAZEBO_MAJOR_VERSION >= 8 202 const ignition::math::Vector3d kVelLinearBody =
203 this->link->RelativeLinearVel();
205 const ignition::math::Vector3d kVelLinearBody =
206 this->link->GetRelativeLinearVel().Ign();
210 #if GAZEBO_MAJOR_VERSION >= 8 211 const ignition::math::Vector3d kVelAngularBody =
212 this->link->RelativeAngularVel();
214 const ignition::math::Vector3d kVelAngularBody =
215 this->link->GetRelativeAngularVel().Ign();
222 const ignition::math::Vector3d kAccelLinearBody =
223 (kVelLinearBody - this->prevLinVel) / dt;
224 this->prevLinVel = kVelLinearBody;
226 const ignition::math::Vector3d kAccelAngularBody =
227 (kVelAngularBody - this->prevAngVel) / dt;
228 this->prevAngVel = kVelAngularBody;
232 Eigen::VectorXd stateDot = Eigen::VectorXd(6);
233 Eigen::VectorXd state = Eigen::VectorXd(6);
234 Eigen::MatrixXd Cmat = Eigen::MatrixXd::Zero(6, 6);
235 Eigen::MatrixXd Dmat = Eigen::MatrixXd::Zero(6, 6);
237 stateDot << kAccelLinearBody.X(), kAccelLinearBody.Y(), kAccelLinearBody.Z(),
238 kAccelAngularBody.X(), kAccelAngularBody.Y(), kAccelAngularBody.Z();
240 state << kVelLinearBody.X(), kVelLinearBody.Y(), kVelLinearBody.Z(),
241 kVelAngularBody.X(), kVelAngularBody.Y(), kVelAngularBody.Z();
244 const Eigen::VectorXd kAmassVec = -1.0 * this->Ma * stateDot;
249 Cmat(0, 5) = this->paramYdotV * kVelLinearBody.Y();
250 Cmat(1, 5) = this->paramXdotU * kVelLinearBody.X();
251 Cmat(5, 0) = this->paramYdotV * kVelLinearBody.Y();
252 Cmat(5, 1) = this->paramXdotU * kVelLinearBody.X();
255 Dmat(0, 0) = this->paramXu + this->paramXuu * std::abs(kVelLinearBody.X());
256 Dmat(1, 1) = this->paramYv + this->paramYvv * std::abs(kVelLinearBody.Y());
257 Dmat(2, 2) = this->paramZw;
258 Dmat(3, 3) = this->paramKp;
259 Dmat(4, 4) = this->paramMq;
260 Dmat(5, 5) = this->paramNr + this->paramNrr * std::abs(kVelAngularBody.Z());
262 const Eigen::VectorXd kDvec = -1.0 * Dmat * state;
263 ROS_DEBUG_STREAM_THROTTLE(1.0,
"Dvec :\n" << kDvec);
273 const Eigen::VectorXd kForceSum = kAmassVec + kDvec;
276 ROS_DEBUG_STREAM_THROTTLE(1.0,
"forceSum :\n" << kForceSum);
279 this->link->AddRelativeForce(
280 ignition::math::Vector3d(kForceSum(0), kForceSum(1), kForceSum(2)));
281 this->link->AddRelativeTorque(
282 ignition::math::Vector3d(kForceSum(3), kForceSum(4), kForceSum(5)));
286 tf2::Vector3 bpnt(0, 0, 0);
288 tf2::Vector3 bpntW(0, 0, 0);
290 for (
int ii = 0; ii < 2; ii++)
293 bpnt.setY((ii*2.0-1.0)*this->paramBoatWidth/2.0);
295 for (
int jj = 1; jj <= this->paramLengthN; jj++)
297 bpnt.setX(((jj - 0.5) / (static_cast<float>(this->paramLengthN)) - 0.5) *
298 this->paramBoatLength);
301 bpntW = xformV * bpnt;
304 ROS_DEBUG_STREAM_THROTTLE(1.0,
"[" << ii <<
"," << jj <<
305 "] grid points" << bpnt.x() <<
"," << bpnt.y() <<
"," << bpnt.z());
306 ROS_DEBUG_STREAM_THROTTLE(1.0,
"v frame euler " << kEuler);
307 ROS_DEBUG_STREAM_THROTTLE(1.0,
"in water frame" << bpntW.x() <<
"," <<
308 bpntW.y() <<
"," << bpntW.z());
311 const float kDdz = kPose.Pos().Z() + bpntW.z();
313 << bpntW.z() <<
", dd: " << kDdz);
317 ignition::math::Vector3d X;
318 X.X() = kPose.Pos().X() + bpntW.x();
319 X.Y() = kPose.Pos().Y() + bpntW.y();
322 double simTime = kTimeNow.Double();
326 *waveParams, X, simTime);
329 double dz = depth + X.Z();
332 double deltaZ = (this->waterLevel + dz) - kDdz;
333 deltaZ = std::max(deltaZ, 0.0);
334 deltaZ = std::min(deltaZ, this->paramHullRadius);
336 const float kBuoyForce = CircleSegment(this->paramHullRadius, deltaZ) *
337 this->paramBoatLength/(
static_cast<float>(this->paramLengthN)) *
344 this->link->AddForceAtRelativePosition(
345 ignition::math::Vector3d(0, 0, kBuoyForce),
346 ignition::math::Vector3d(bpnt.x(), bpnt.y(), bpnt.z()));
#define ROS_DEBUG_STREAM_THROTTLE(period, args)
GZ_REGISTER_MODEL_PLUGIN(UsvDynamicsPlugin)
#define ROS_DEBUG_STREAM(args)
static std::shared_ptr< const WaveParameters > GetWaveParams(gazebo::physics::WorldPtr _world, const std::string &_waveModelName)
static double ComputeDepthSimply(const WaveParameters &_waveParams, const ignition::math::Vector3d &_point, double time, double time_init=0)
#define ROS_INFO_STREAM(args)
void setEulerYPR(tf2Scalar eulerZ, tf2Scalar eulerY, tf2Scalar eulerX)
void getRotation(Quaternion &q) const