usv_gazebo_dynamics_plugin.cc
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 #include <ros/ros.h>
20 
21 #include <cmath>
22 #include <functional>
23 #include <sstream>
24 #include <algorithm>
25 
26 #include <ignition/math/Pose3.hh>
27 
29 
30 #define GRAVITY 9.815
31 
32 using namespace asv;
33 using namespace gazebo;
34 
36 UsvDynamicsPlugin::UsvDynamicsPlugin()
37 {
38 }
39 
41 double UsvDynamicsPlugin::SdfParamDouble(sdf::ElementPtr _sdfPtr,
42  const std::string &_paramName, const double _defaultVal) const
43 {
44  if (!_sdfPtr->HasElement(_paramName))
45  {
46  ROS_INFO_STREAM("Parameter <" << _paramName << "> not found: "
47  "Using default value of <" << _defaultVal << ">.");
48  return _defaultVal;
49  }
50 
51  double val = _sdfPtr->Get<double>(_paramName);
52  ROS_DEBUG_STREAM("Parameter found - setting <" << _paramName <<
53  "> to <" << val << ">.");
54  return val;
55 }
56 
58 void UsvDynamicsPlugin::Load(physics::ModelPtr _model, sdf::ElementPtr _sdf)
59 {
60  ROS_DEBUG("Loading usv_gazebo_dynamics_plugin");
61  this->world = _model->GetWorld();
62 
63  // Get parameters from SDF
64  std::string linkName;
65  if (!_sdf->HasElement("bodyName") ||
66  !_sdf->GetElement("bodyName")->GetValue())
67  {
68  this->link = _model->GetLink();
69  linkName = this->link->GetName();
70  ROS_INFO_STREAM("Did not find SDF parameter bodyName");
71  }
72  else
73  {
74  linkName = _sdf->GetElement("bodyName")->Get<std::string>();
75  this->link = _model->GetLink(linkName);
76 
77  ROS_DEBUG_STREAM("Found SDF parameter bodyName as <" << linkName<< ">");
78  }
79  if (!this->link)
80  {
81  ROS_FATAL("usv_gazebo_dynamics_plugin error: bodyName: %s does not exist\n",
82  linkName.c_str());
83  return;
84  }
85  else
86  {
87  ROS_DEBUG_STREAM("USV Dynamics Model Link Name = " << linkName);
88  }
89 
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);
107 
108  if (!_sdf->HasElement("length_n"))
109  {
110  int defaultVal = 2;
111  ROS_INFO_STREAM("Parameter <length_n> not found: "
112  "Using default value of <" << defaultVal << ">.");
113  this->paramLengthN = defaultVal;
114  }
115  else
116  {
117  this->paramLengthN = _sdf->GetElement("length_n")->Get<int>();
118  }
119 
120 
121  // Wave model
122  if (_sdf->HasElement("wave_model"))
123  {
124  this->waveModelName = _sdf->Get<std::string>("wave_model");
125  }
126  this->waveParams = nullptr;
127 
128  // Get inertia and mass of vessel
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();
133  #else
134  const ignition::math::Vector3d kInertia =
135  this->link->GetInertial()->GetPrincipalMoments().Ign();
136  const double kMass = this->link->GetInertial()->GetMass();
137  #endif
138 
139  // Report some of the pertinent parameters for verification
140  ROS_DEBUG("USV Dynamics Parameters: From URDF XACRO model definition");
141  ROS_DEBUG_STREAM("Vessel Mass (rigid-body): " << kMass);
142  ROS_DEBUG_STREAM("Vessel Inertia Vector (rigid-body): X:" << kInertia[0] <<
143  " Y:" << kInertia[1] << " Z:" << kInertia[2]);
144 
145  // Initialize time and odometry position
146  #if GAZEBO_MAJOR_VERSION >= 8
147  this->prevUpdateTime = this->world->SimTime();
148  #else
149  this->prevUpdateTime = this->world->GetSimTime();
150  #endif
151 
152  // Listen to the update event broadcastes every physics iteration.
153  this->updateConnection = event::Events::ConnectWorldUpdateBegin(
154  std::bind(&UsvDynamicsPlugin::Update, this));
155 
156  // Initialize Added Mass Matrix
157  this->Ma = Eigen::MatrixXd(6, 6);
158  this->Ma <<
159  this->paramXdotU, 0, 0, 0, 0, 0,
160  0, this->paramYdotV, 0, 0, 0, 0,
161  0, 0, 0.1, 0, 0, 0,
162  0, 0, 0, 0.1, 0, 0,
163  0, 0, 0, 0, 0.1, 0,
164  0, 0, 0, 0, 0, this->paramNdotR;
165 }
166 
167 double UsvDynamicsPlugin::CircleSegment(double R, double h)
168 {
169  return R*R*acos( (R-h)/R ) - (R-h)*sqrt(2*R*h-h*h);
170 }
171 
173 void UsvDynamicsPlugin::Update()
174 {
175  // If we haven't yet, retrieve the wave parameters from ocean model plugin.
176  if (waveParams == nullptr)
177  {
178  gzmsg << "usv_gazebo_dynamics_plugin: waveParams is null. "
179  << " Trying to get wave parameters from ocean model" << std::endl;
180  this->waveParams = WavefieldModelPlugin::GetWaveParams(
181  this->world, this->waveModelName);
182  }
183 
184  #if GAZEBO_MAJOR_VERSION >= 8
185  const common::Time kTimeNow = this->world->SimTime();
186  #else
187  const common::Time kTimeNow = this->world->GetSimTime();
188  #endif
189  double dt = (kTimeNow - this->prevUpdateTime).Double();
190  this->prevUpdateTime = kTimeNow;
191 
192  // Get Pose/Orientation from Gazebo (if no state subscriber is active)
193  #if GAZEBO_MAJOR_VERSION >= 8
194  const ignition::math::Pose3d kPose = this->link->WorldPose();
195  #else
196  const ignition::math::Pose3d kPose = this->link->GetWorldPose().Ign();
197  #endif
198  const ignition::math::Vector3d kEuler = kPose.Rot().Euler();
199 
200  // Get body-centered linear and angular rates
201  #if GAZEBO_MAJOR_VERSION >= 8
202  const ignition::math::Vector3d kVelLinearBody =
203  this->link->RelativeLinearVel();
204  #else
205  const ignition::math::Vector3d kVelLinearBody =
206  this->link->GetRelativeLinearVel().Ign();
207  #endif
208  ROS_DEBUG_STREAM_THROTTLE(0.5, "Vel linear: " << kVelLinearBody);
209 
210  #if GAZEBO_MAJOR_VERSION >= 8
211  const ignition::math::Vector3d kVelAngularBody =
212  this->link->RelativeAngularVel();
213  #else
214  const ignition::math::Vector3d kVelAngularBody =
215  this->link->GetRelativeAngularVel().Ign();
216  #endif
217  ROS_DEBUG_STREAM_THROTTLE(0.5, "Vel angular: " << kVelAngularBody);
218 
219  // Estimate the linear and angular accelerations.
220  // Note the the GetRelativeLinearAccel() and AngularAccel() functions
221  // appear to be unreliable
222  const ignition::math::Vector3d kAccelLinearBody =
223  (kVelLinearBody - this->prevLinVel) / dt;
224  this->prevLinVel = kVelLinearBody;
225  ROS_DEBUG_STREAM_THROTTLE(0.5, "Accel linear: " << kAccelLinearBody);
226  const ignition::math::Vector3d kAccelAngularBody =
227  (kVelAngularBody - this->prevAngVel) / dt;
228  this->prevAngVel = kVelAngularBody;
229  ROS_DEBUG_STREAM_THROTTLE(0.5, "Accel angular: " << kAccelAngularBody);
230 
231  // Create state and derivative of state (accelerations)
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);
236 
237  stateDot << kAccelLinearBody.X(), kAccelLinearBody.Y(), kAccelLinearBody.Z(),
238  kAccelAngularBody.X(), kAccelAngularBody.Y(), kAccelAngularBody.Z();
239 
240  state << kVelLinearBody.X(), kVelLinearBody.Y(), kVelLinearBody.Z(),
241  kVelAngularBody.X(), kVelAngularBody.Y(), kVelAngularBody.Z();
242 
243  // Added Mass
244  const Eigen::VectorXd kAmassVec = -1.0 * this->Ma * stateDot;
245  ROS_DEBUG_STREAM_THROTTLE(1.0, "stateDot: \n" << stateDot);
246  ROS_DEBUG_STREAM_THROTTLE(1.0, "amassVec :\n" << kAmassVec);
247 
248  // Coriolis - added mass components
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();
253 
254  // Drag
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());
261  ROS_DEBUG_STREAM_THROTTLE(1.0, "Dmat :\n" << Dmat);
262  const Eigen::VectorXd kDvec = -1.0 * Dmat * state;
263  ROS_DEBUG_STREAM_THROTTLE(1.0, "Dvec :\n" << kDvec);
264 
265  // Vehicle frame transform
267  tf2::Matrix3x3 m;
268  m.setEulerYPR(kEuler.Z(), kEuler.Y(), kEuler.X());
269  m.getRotation(vq);
270  tf2::Transform xformV = tf2::Transform(vq);
271 
272  // Sum all forces - in body frame
273  const Eigen::VectorXd kForceSum = kAmassVec + kDvec;
274 
275  // Forces in fixed frame
276  ROS_DEBUG_STREAM_THROTTLE(1.0, "forceSum :\n" << kForceSum);
277 
278  // Add dynamic forces/torques to link at CG
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)));
283 
284  // Loop over boat grid points
285  // Grid point location in boat frame - might be able to precalculate these?
286  tf2::Vector3 bpnt(0, 0, 0);
287  // Grid point location in world frame
288  tf2::Vector3 bpntW(0, 0, 0);
289  // For each hull
290  for (int ii = 0; ii < 2; ii++)
291  {
292  // Grid point in boat frame
293  bpnt.setY((ii*2.0-1.0)*this->paramBoatWidth/2.0);
294  // For each length segment
295  for (int jj = 1; jj <= this->paramLengthN; jj++)
296  {
297  bpnt.setX(((jj - 0.5) / (static_cast<float>(this->paramLengthN)) - 0.5) *
298  this->paramBoatLength);
299 
300  // Transform from vessel to water/world frame
301  bpntW = xformV * bpnt;
302 
303  // Debug
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());
309 
310  // Vertical location of boat grid point in world frame
311  const float kDdz = kPose.Pos().Z() + bpntW.z();
312  ROS_DEBUG_STREAM("Z, pose: " << kPose.Pos().Z() << ", bpnt: "
313  << bpntW.z() << ", dd: " << kDdz);
314 
315  // Find vertical displacement of wave field
316  // World location of grid point
317  ignition::math::Vector3d X;
318  X.X() = kPose.Pos().X() + bpntW.x();
319  X.Y() = kPose.Pos().Y() + bpntW.y();
320 
321  // Compute the depth at the grid point.
322  double simTime = kTimeNow.Double();
323  // double depth = WavefieldSampler::ComputeDepthDirectly(
324  // *waveParams, X, simTime);
326  *waveParams, X, simTime);
327 
328  // Vertical wave displacement.
329  double dz = depth + X.Z();
330 
331  // Total z location of boat grid point relative to water surface
332  double deltaZ = (this->waterLevel + dz) - kDdz;
333  deltaZ = std::max(deltaZ, 0.0); // enforce only upward buoy force
334  deltaZ = std::min(deltaZ, this->paramHullRadius);
335  // Buoyancy force at grid point
336  const float kBuoyForce = CircleSegment(this->paramHullRadius, deltaZ) *
337  this->paramBoatLength/(static_cast<float>(this->paramLengthN)) *
338  GRAVITY * this->waterDensity;
339  ROS_DEBUG_STREAM("buoyForce: " << kBuoyForce);
340 
341  // Apply force at grid point
342  // From web, Appears that position is in the link frame
343  // and force is in world frame
344  this->link->AddForceAtRelativePosition(
345  ignition::math::Vector3d(0, 0, kBuoyForce),
346  ignition::math::Vector3d(bpnt.x(), bpnt.y(), bpnt.z()));
347  }
348  }
349 }
350 
351 GZ_REGISTER_MODEL_PLUGIN(UsvDynamicsPlugin);
#define ROS_DEBUG_STREAM_THROTTLE(rate, args)
#define ROS_FATAL(...)
GZ_REGISTER_MODEL_PLUGIN(UsvDynamicsPlugin)
#define ROS_DEBUG_STREAM(args)
#define GRAVITY
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)
void getRotation(Quaternion &q) const
#define ROS_INFO_STREAM(args)
void setEulerYPR(tf2Scalar eulerZ, tf2Scalar eulerY, tf2Scalar eulerX)
#define ROS_DEBUG(...)


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