Rigid Body Dynamics Library
Model_formatted.cc
Go to the documentation of this file.
1 /*
2  * RBDL - Rigid Body Dynamics Library
3  * Copyright (c) 2011-2018 Martin Felis <martin@fysx.org>
4  *
5  * Licensed under the zlib license. See LICENSE for more details.
6  */
7 
8 #include <assert.h>
9 
10 #include <iostream>
11 #include <limits>
12 
13 #include "rbdl/Body.h"
14 #include "rbdl/Joint.h"
15 #include "rbdl/Logging.h"
16 #include "rbdl/Model.h"
17 #include "rbdl/rbdl_mathutils.h"
18 
19 using namespace RigidBodyDynamics;
20 using namespace RigidBodyDynamics::Math;
21 
22 Model::Model() {
23  Body root_body;
24  Joint root_joint;
25 
26  Vector3d zero_position(0., 0., 0.);
27  SpatialVector zero_spatial(0., 0., 0., 0., 0., 0.);
28 
29  // structural information
30  lambda.push_back(0);
31  lambda_q.push_back(0);
32  mu.push_back(std::vector<unsigned int>());
33  dof_count = 0;
34  q_size = 0;
35  qdot_size = 0;
36  previously_added_body_id = 0;
37 
38  gravity = Vector3d(0., -9.81, 0.);
39 
40  // state information
41  v.push_back(zero_spatial);
42  a.push_back(zero_spatial);
43 
44  // Joints
45  mJoints.push_back(root_joint);
46  S.push_back(zero_spatial);
47  X_T.push_back(SpatialTransform());
48 
49  v_J.push_back(zero_spatial);
50  c_J.push_back(zero_spatial);
51 
52  // Spherical joints
53  multdof3_S.push_back(Matrix63::Zero());
54  multdof3_U.push_back(Matrix63::Zero());
55  multdof3_Dinv.push_back(Matrix3d::Zero());
56  multdof3_u.push_back(Vector3d::Zero());
57  multdof3_w_index.push_back(0);
58 
59  // Dynamic variables
60  c.push_back(zero_spatial);
61  IA.push_back(SpatialMatrix::Identity());
62  pA.push_back(zero_spatial);
63  U.push_back(zero_spatial);
64 
65  u = VectorNd::Zero(1);
66  d = VectorNd::Zero(1);
67 
68  f.push_back(zero_spatial);
69  SpatialRigidBodyInertia rbi(0., Vector3d(0., 0., 0.), Matrix3d::Zero(3, 3));
70  Ic.push_back(rbi);
71  I.push_back(rbi);
72  hc.push_back(zero_spatial);
73  hdotc.push_back(zero_spatial);
74 
75  // Bodies
76  X_lambda.push_back(SpatialTransform());
77  X_base.push_back(SpatialTransform());
78 
79  mBodies.push_back(root_body);
80  mBodyNameMap["ROOT"] = 0;
81 
82  fixed_body_discriminator = std::numeric_limits<unsigned int>::max() / 2;
83 }
84 
85 unsigned int AddBodyFixedJoint(
86  Model &model,
87  const unsigned int parent_id,
88  const SpatialTransform &joint_frame,
89  const Joint &UNUSED(joint),
90  const Body &body,
91  std::string body_name) {
93  fbody.mMovableParent = parent_id;
94  fbody.mParentTransform = joint_frame;
95 
96  if (model.IsFixedBodyId(parent_id)) {
97  FixedBody fixed_parent =
98  model.mFixedBodies[parent_id - model.fixed_body_discriminator];
99 
100  fbody.mMovableParent = fixed_parent.mMovableParent;
101  fbody.mParentTransform = joint_frame * fixed_parent.mParentTransform;
102  }
103 
104  // merge the two bodies
105  Body parent_body = model.mBodies[fbody.mMovableParent];
106  parent_body.Join(fbody.mParentTransform, body);
107  model.mBodies[fbody.mMovableParent] = parent_body;
108  model.I[fbody.mMovableParent] =
110  parent_body.mMass,
111  parent_body.mCenterOfMass,
112  parent_body.mInertia);
113 
114  model.mFixedBodies.push_back(fbody);
115 
116  if (model.mFixedBodies.size() > std::numeric_limits<unsigned int>::max()
117  - model.fixed_body_discriminator) {
118  std::cerr << "Error: cannot add more than "
119  << std::numeric_limits<unsigned int>::max()
120  - model.mFixedBodies.size()
121  << " fixed bodies. You need to modify "
122  << "Model::fixed_body_discriminator for this." << std::endl;
123  assert(0);
124  abort();
125  }
126 
127  if (body_name.size() != 0) {
128  if (model.mBodyNameMap.find(body_name) != model.mBodyNameMap.end()) {
129  std::cerr << "Error: Body with name '" << body_name << "' already exists!"
130  << std::endl;
131  assert(0);
132  abort();
133  }
134  model.mBodyNameMap[body_name] =
135  model.mFixedBodies.size() + model.fixed_body_discriminator - 1;
136  }
137 
138  return model.mFixedBodies.size() + model.fixed_body_discriminator - 1;
139 }
140 
141 unsigned int AddBodyMultiDofJoint(
142  Model &model,
143  const unsigned int parent_id,
144  const SpatialTransform &joint_frame,
145  const Joint &joint,
146  const Body &body,
147  std::string body_name) {
148  // Here we emulate multi DoF joints by simply adding nullbodies. This
149  // allows us to use fixed size elements for S,v,a, etc. which is very
150  // fast in Eigen.
151  unsigned int joint_count = 0;
152  if (joint.mJointType == JointType1DoF)
153  joint_count = 1;
154  else if (joint.mJointType == JointType2DoF)
155  joint_count = 2;
156  else if (joint.mJointType == JointType3DoF)
157  joint_count = 3;
158  else if (joint.mJointType == JointType4DoF)
159  joint_count = 4;
160  else if (joint.mJointType == JointType5DoF)
161  joint_count = 5;
162  else if (joint.mJointType == JointType6DoF)
163  joint_count = 6;
164  else if (joint.mJointType == JointTypeFloatingBase)
165  // no action required
166  {
167  } else {
168  std::cerr << "Error: Invalid joint type: " << joint.mJointType << std::endl;
169 
170  assert(0 && !"Invalid joint type!");
171  }
172 
173  Body null_body(0., Vector3d(0., 0., 0.), Vector3d(0., 0., 0.));
174  null_body.mIsVirtual = true;
175 
176  unsigned int null_parent = parent_id;
177  SpatialTransform joint_frame_transform;
178 
179  if (joint.mJointType == JointTypeFloatingBase) {
180  null_parent = model.AddBody(
181  parent_id,
182  joint_frame,
184  null_body);
185 
186  return model.AddBody(
187  null_parent,
190  body,
191  body_name);
192  }
193 
194  Joint single_dof_joint;
195  unsigned int j;
196 
197  // Here we add multiple virtual bodies that have no mass or inertia for
198  // which each is attached to the model with a single degree of freedom
199  // joint.
200  for (j = 0; j < joint_count; j++) {
201  single_dof_joint = Joint(joint.mJointAxes[j]);
202 
203  if (single_dof_joint.mJointType == JointType1DoF) {
204  Vector3d rotation(
205  joint.mJointAxes[j][0],
206  joint.mJointAxes[j][1],
207  joint.mJointAxes[j][2]);
208  Vector3d translation(
209  joint.mJointAxes[j][3],
210  joint.mJointAxes[j][4],
211  joint.mJointAxes[j][5]);
212 
213  if (rotation == Vector3d(0., 0., 0.)) {
214  single_dof_joint = Joint(JointTypePrismatic, translation);
215  } else if (translation == Vector3d(0., 0., 0.)) {
216  single_dof_joint = Joint(JointTypeRevolute, rotation);
217  }
218  }
219 
220  // the first joint has to be transformed by joint_frame, all the
221  // others must have a null transformation
222  if (j == 0)
223  joint_frame_transform = joint_frame;
224  else
225  joint_frame_transform = SpatialTransform();
226 
227  if (j == joint_count - 1)
228  // if we are at the last we must add the real body
229  break;
230  else {
231  // otherwise we just add an intermediate body
232  null_parent = model.AddBody(
233  null_parent,
234  joint_frame_transform,
235  single_dof_joint,
236  null_body);
237  }
238  }
239 
240  return model.AddBody(
241  null_parent,
242  joint_frame_transform,
243  single_dof_joint,
244  body,
245  body_name);
246 }
247 
248 unsigned int Model::AddBody(
249  const unsigned int parent_id,
250  const SpatialTransform &joint_frame,
251  const Joint &joint,
252  const Body &body,
253  std::string body_name) {
254  assert(lambda.size() > 0);
255  assert(joint.mJointType != JointTypeUndefined);
256 
257  if (joint.mJointType == JointTypeFixed) {
258  previously_added_body_id = AddBodyFixedJoint(
259  *this,
260  parent_id,
261  joint_frame,
262  joint,
263  body,
264  body_name);
265 
266  return previously_added_body_id;
267  } else if (
268  (joint.mJointType == JointTypeSpherical)
269  || (joint.mJointType == JointTypeEulerZYX)
270  || (joint.mJointType == JointTypeEulerXYZ)
271  || (joint.mJointType == JointTypeEulerYXZ)
272  || (joint.mJointType == JointTypeEulerZXY)
273  || (joint.mJointType == JointTypeTranslationXYZ)
274  || (joint.mJointType == JointTypeCustom)) {
275  // no action required
276  } else if (
278  && joint.mJointType != JointTypeRevolute
279  && joint.mJointType != JointTypeRevoluteX
280  && joint.mJointType != JointTypeRevoluteY
281  && joint.mJointType != JointTypeRevoluteZ
282  && joint.mJointType != JointTypeHelical) {
283  previously_added_body_id = AddBodyMultiDofJoint(
284  *this,
285  parent_id,
286  joint_frame,
287  joint,
288  body,
289  body_name);
290  return previously_added_body_id;
291  }
292 
293  // If we add the body to a fixed body we have to make sure that we
294  // actually add it to its movable parent.
295  unsigned int movable_parent_id = parent_id;
296  SpatialTransform movable_parent_transform;
297 
298  if (IsFixedBodyId(parent_id)) {
299  unsigned int fbody_id = parent_id - fixed_body_discriminator;
300  movable_parent_id = mFixedBodies[fbody_id].mMovableParent;
301  movable_parent_transform = mFixedBodies[fbody_id].mParentTransform;
302  }
303 
304  // structural information
305  lambda.push_back(movable_parent_id);
306  unsigned int lambda_q_last = mJoints[mJoints.size() - 1].q_index;
307 
308  if (mJoints[mJoints.size() - 1].mDoFCount > 0
309  && mJoints[mJoints.size() - 1].mJointType != JointTypeCustom) {
310  lambda_q_last = lambda_q_last + mJoints[mJoints.size() - 1].mDoFCount;
311  } else if (mJoints[mJoints.size() - 1].mJointType == JointTypeCustom) {
312  // unsigned int custom_index = mJoints[mJoints.size() -
313  // 1].custom_joint_index;
314  lambda_q_last =
315  lambda_q_last + mCustomJoints[mCustomJoints.size() - 1]->mDoFCount;
316  }
317 
318  for (unsigned int i = 0; i < joint.mDoFCount; i++) {
319  lambda_q.push_back(lambda_q_last + i);
320  }
321  mu.push_back(std::vector<unsigned int>());
322  mu.at(movable_parent_id).push_back(mBodies.size());
323 
324  // Bodies
325  X_lambda.push_back(SpatialTransform());
326  X_base.push_back(SpatialTransform());
327  mBodies.push_back(body);
328 
329  if (body_name.size() != 0) {
330  if (mBodyNameMap.find(body_name) != mBodyNameMap.end()) {
331  std::cerr << "Error: Body with name '" << body_name << "' already exists!"
332  << std::endl;
333  assert(0);
334  abort();
335  }
336  mBodyNameMap[body_name] = mBodies.size() - 1;
337  }
338 
339  // state information
340  v.push_back(SpatialVector(0., 0., 0., 0., 0., 0.));
341  a.push_back(SpatialVector(0., 0., 0., 0., 0., 0.));
342 
343  // Joints
344  unsigned int prev_joint_index = mJoints.size() - 1;
345  mJoints.push_back(joint);
346 
347  if (mJoints[prev_joint_index].mJointType != JointTypeCustom) {
348  mJoints[mJoints.size() - 1].q_index =
349  mJoints[prev_joint_index].q_index + mJoints[prev_joint_index].mDoFCount;
350  } else {
351  mJoints[mJoints.size() - 1].q_index =
352  mJoints[prev_joint_index].q_index + mJoints[prev_joint_index].mDoFCount;
353  }
354 
355  S.push_back(joint.mJointAxes[0]);
356 
357  // Joint state variables
358  v_J.push_back(joint.mJointAxes[0]);
359  c_J.push_back(SpatialVector(0., 0., 0., 0., 0., 0.));
360 
361  // workspace for joints with 3 dof
362  multdof3_S.push_back(Matrix63::Zero(6, 3));
363  multdof3_U.push_back(Matrix63::Zero());
364  multdof3_Dinv.push_back(Matrix3d::Zero());
365  multdof3_u.push_back(Vector3d::Zero());
366  multdof3_w_index.push_back(0);
367 
368  dof_count = dof_count + joint.mDoFCount;
369 
370  // update the w components of the Quaternions. They are stored at the end
371  // of the q vector
372  int multdof3_joint_counter = 0;
373  // int mCustomJoint_joint_counter = 0;
374  for (unsigned int i = 1; i < mJoints.size(); i++) {
375  if (mJoints[i].mJointType == JointTypeSpherical) {
376  multdof3_w_index[i] = dof_count + multdof3_joint_counter;
377  multdof3_joint_counter++;
378  }
379  }
380 
381  q_size = dof_count + multdof3_joint_counter;
382 
383  qdot_size = qdot_size + joint.mDoFCount;
384 
385  // we have to invert the transformation as it is later always used from the
386  // child bodies perspective.
387  X_T.push_back(joint_frame * movable_parent_transform);
388 
389  // Dynamic variables
390  c.push_back(SpatialVector(0., 0., 0., 0., 0., 0.));
391  IA.push_back(SpatialMatrix::Zero(6, 6));
392  pA.push_back(SpatialVector(0., 0., 0., 0., 0., 0.));
393  U.push_back(SpatialVector(0., 0., 0., 0., 0., 0.));
394 
395  d = VectorNd::Zero(mBodies.size());
396  u = VectorNd::Zero(mBodies.size());
397 
398  f.push_back(SpatialVector(0., 0., 0., 0., 0., 0.));
399 
402  body.mMass,
403  body.mCenterOfMass,
404  body.mInertia);
405 
406  Ic.push_back(rbi);
407  I.push_back(rbi);
408  hc.push_back(SpatialVector(0., 0., 0., 0., 0., 0.));
409  hdotc.push_back(SpatialVector(0., 0., 0., 0., 0., 0.));
410 
411  if (mBodies.size() == fixed_body_discriminator) {
412  std::cerr << "Error: cannot add more than " << fixed_body_discriminator
413  << " movable bodies. You need to modify "
414  "Model::fixed_body_discriminator for this."
415  << std::endl;
416  assert(0);
417  abort();
418  }
419 
420  previously_added_body_id = mBodies.size() - 1;
421 
422  mJointUpdateOrder.clear();
423 
424  // update the joint order computation
425  std::vector<std::pair<JointType, unsigned int>> joint_types;
426  for (unsigned int i = 0; i < mJoints.size(); i++) {
427  joint_types.push_back(
428  std::pair<JointType, unsigned int>(mJoints[i].mJointType, i));
429  mJointUpdateOrder.push_back(mJoints[i].mJointType);
430  }
431 
432  mJointUpdateOrder.clear();
433  JointType current_joint_type = JointTypeUndefined;
434  while (joint_types.size() != 0) {
435  current_joint_type = joint_types[0].first;
436 
437  std::vector<std::pair<JointType, unsigned int>>::iterator type_iter =
438  joint_types.begin();
439 
440  while (type_iter != joint_types.end()) {
441  if (type_iter->first == current_joint_type) {
442  mJointUpdateOrder.push_back(type_iter->second);
443  type_iter = joint_types.erase(type_iter);
444  } else {
445  ++type_iter;
446  }
447  }
448  }
449 
450  // for (unsigned int i = 0; i < mJointUpdateOrder.size(); i++) {
451  // std::cout << "i = " << i << ": joint_id = " << mJointUpdateOrder[i]
452  // << " joint_type = " << mJoints[mJointUpdateOrder[i]].mJointType <<
453  // std::endl;
454  // }
455 
456  return previously_added_body_id;
457 }
458 
459 unsigned int Model::AppendBody(
460  const Math::SpatialTransform &joint_frame,
461  const Joint &joint,
462  const Body &body,
463  std::string body_name) {
464  return Model::AddBody(
465  previously_added_body_id,
466  joint_frame,
467  joint,
468  body,
469  body_name);
470 }
471 
472 unsigned int Model::AddBodyCustomJoint(
473  const unsigned int parent_id,
474  const Math::SpatialTransform &joint_frame,
475  CustomJoint *custom_joint,
476  const Body &body,
477  std::string body_name) {
478  Joint proxy_joint(JointTypeCustom, custom_joint->mDoFCount);
479  proxy_joint.custom_joint_index = mCustomJoints.size();
480  // proxy_joint.mDoFCount = custom_joint->mDoFCount; //MM added. Otherwise
481  // model.q_size = 0, which is not good.
482 
483  mCustomJoints.push_back(custom_joint);
484 
485  unsigned int body_id =
486  AddBody(parent_id, joint_frame, proxy_joint, body, body_name);
487 
488  return body_id;
489 }
Compact representation of spatial transformations.
Compact representation for Spatial Inertia.
static SpatialRigidBodyInertia createFromMassComInertiaC(double mass, const Vector3d &com, const Matrix3d &inertia_C)
Emulated 2 DoF joint.
Definition: Joint.h:198
unsigned int AddBodyMultiDofJoint(Model &model, const unsigned int parent_id, const SpatialTransform &joint_frame, const Joint &joint, const Body &body, std::string body_name)
bool IsFixedBodyId(unsigned int body_id)
Checks whether the body is rigidly attached to another body.
Definition: Model.h:370
Contains all information about the rigid body model.
Definition: Model.h:121
Emulated 4 DoF joint.
Definition: Joint.h:200
SpatialVector_t SpatialVector
Definition: rbdl_math.h:56
3 DoF joint that uses Euler ZXY convention (faster than emulated multi DoF joints).
Definition: Joint.h:192
std::vector< Body > mBodies
All bodies 0 ... N_B, including the base.
Definition: Model.h:262
unsigned int AddBody(const unsigned int parent_id, const Math::SpatialTransform &joint_frame, const Joint &joint, const Body &body, std::string body_name="")
Connects a given body to the model.
Definition: Model.cc:249
Namespace for all structures of the RigidBodyDynamics library.
Definition: Constraints.cc:23
Fixed joint which causes the inertial properties to be merged with the parent body.
Definition: Joint.h:195
std::vector< Math::SpatialRigidBodyInertia > I
The spatial inertia of body i (used only in CompositeRigidBodyAlgorithm())
Definition: Model.h:222
unsigned int mMovableParent
Id of the movable body that this fixed body is attached to.
Definition: Body.h:195
JointType
General types of joints.
Definition: Joint.h:181
void Join(const Math::SpatialTransform &transform, const Body &other_body)
Joins inertial parameters of two bodies to create a composite body.
Definition: Body.h:104
std::vector< FixedBody > mFixedBodies
All bodies that are attached to a body via a fixed joint.
Definition: Model.h:240
unsigned int AddBodyFixedJoint(Model &model, const unsigned int parent_id, const SpatialTransform &joint_frame, const Joint &UNUSED(joint), const Body &body, std::string body_name)
3 DoF joint that uses Euler ZYX convention (faster than emulated multi DoF joints).
Definition: Joint.h:189
unsigned int AppendBody(const Math::SpatialTransform &joint_frame, const Joint &joint, const Body &body, std::string body_name="")
Adds a Body to the model such that the previously added Body is the Parent.
Definition: Model.cc:460
Math::Matrix3d mInertia
Inertia matrix at the center of mass.
Definition: Body.h:175
3 DoF joint that uses Euler XYZ convention (faster than emulated multi DoF joints).
Definition: Joint.h:190
Math::Vector3d mCenterOfMass
The position of the center of mass in body coordinates.
Definition: Body.h:173
unsigned int mDoFCount
Number of degrees of freedom of the joint. Note: CustomJoints.
Definition: Joint.h:642
Math types such as vectors and matrices and utility functions.
unsigned int AddBodyCustomJoint(const unsigned int parent_id, const Math::SpatialTransform &joint_frame, CustomJoint *custom_joint, const Body &body, std::string body_name="")
Definition: Model.cc:473
Math::SpatialTransform mParentTransform
Transforms spatial quantities expressed for the parent to the.
Definition: Body.h:198
Keeps the information of a body and how it is attached to another body.
Definition: Body.h:186
A 6-DoF joint for floating-base (or freeflyer) systems.
Definition: Joint.h:194
unsigned int fixed_body_discriminator
Value that is used to discriminate between fixed and movable bodies.
Definition: Model.h:253
double mMass
The mass of the body.
Definition: Body.h:168
Emulated 6 DoF joint.
Definition: Joint.h:202
static FixedBody CreateFromBody(const Body &body)
Definition: Body.h:201
Emulated 3 DoF joint.
Definition: Joint.h:199
JointType mJointType
Type of joint.
Definition: Joint.h:638
3 DoF joint using Quaternions for joint positional variables and angular velocity for joint velocity ...
Definition: Joint.h:188
Describes a joint relative to the predecessor body.
Definition: Joint.h:212
3 DoF joint that uses Euler YXZ convention (faster than emulated multi DoF joints).
Definition: Joint.h:191
std::map< std::string, unsigned int > mBodyNameMap
Human readable names for the bodies.
Definition: Model.h:265
Math::SpatialVector * mJointAxes
The spatial axes of the joint.
Definition: Joint.h:636
Emulated 5 DoF joint.
Definition: Joint.h:201
Describes all properties of a single body.
Definition: Body.h:26
User defined joints of varying size.
Definition: Joint.h:203