Robot Dynamics Library
Joint.hpp
Go to the documentation of this file.
1 // Copyright (c) 2017 Jordan Lack <jlack1987@gmail.com>
2 // Copyright (c) 2011-2016 Martin Felis <martin.felis@iwr.uni-heidelberg.de>
3 // RDL - Robot Dynamics Library
4 // Licensed under the zlib license. See LICENSE for more details.
5 
6 #ifndef __RDL_JOINT_H__
7 #define __RDL_JOINT_H__
8 
13 #include <assert.h>
14 #include <iostream>
17 namespace RobotDynamics
18 {
19 struct Model;
20 
182 {
190  // angular velocity for joint velocity variables.
192  // multi DoF joints).
194  // multi DoF joints).
196  // multi DoF joints).
200  // the parent body.
208 };
209 
222 struct Joint
223 {
225  {
226  }
227 
228  explicit Joint(JointType type) : mJointAxes(nullptr), mJointType(type), mDoFCount(0), q_index(0), custom_joint_index(-1)
229  {
230  if (type == JointTypeRevoluteX)
231  {
232  mDoFCount = 1;
234  mJointAxes[0] = Math::SpatialVector(1., 0., 0., 0., 0., 0.);
235  }
236  else if (type == JointTypeRevoluteY)
237  {
238  mDoFCount = 1;
240  mJointAxes[0] = Math::SpatialVector(0., 1., 0., 0., 0., 0.);
241  }
242  else if (type == JointTypeRevoluteZ)
243  {
244  mDoFCount = 1;
246  mJointAxes[0] = Math::SpatialVector(0., 0., 1., 0., 0., 0.);
247  }
248  else if (type == JointTypeSpherical)
249  {
250  mDoFCount = 3;
251 
253 
254  mJointAxes[0] = Math::SpatialVector(0., 0., 1., 0., 0., 0.);
255  mJointAxes[1] = Math::SpatialVector(0., 1., 0., 0., 0., 0.);
256  mJointAxes[2] = Math::SpatialVector(1., 0., 0., 0., 0., 0.);
257  }
258  else if (type == JointTypeEulerZYX)
259  {
260  mDoFCount = 3;
261 
263 
264  mJointAxes[0] = Math::SpatialVector(0., 0., 1., 0., 0., 0.);
265  mJointAxes[1] = Math::SpatialVector(0., 1., 0., 0., 0., 0.);
266  mJointAxes[2] = Math::SpatialVector(1., 0., 0., 0., 0., 0.);
267  }
268  else if (type == JointTypeEulerXYZ)
269  {
270  mDoFCount = 3;
271 
273 
274  mJointAxes[0] = Math::SpatialVector(1., 0., 0., 0., 0., 0.);
275  mJointAxes[1] = Math::SpatialVector(0., 1., 0., 0., 0., 0.);
276  mJointAxes[2] = Math::SpatialVector(0., 0., 1., 0., 0., 0.);
277  }
278  else if (type == JointTypeEulerYXZ)
279  {
280  mDoFCount = 3;
281 
283 
284  mJointAxes[0] = Math::SpatialVector(0., 1., 0., 0., 0., 0.);
285  mJointAxes[1] = Math::SpatialVector(1., 0., 0., 0., 0., 0.);
286  mJointAxes[2] = Math::SpatialVector(0., 0., 1., 0., 0., 0.);
287  }
288  else if (type == JointTypeTranslationXYZ)
289  {
290  mDoFCount = 3;
291 
293 
294  mJointAxes[0] = Math::SpatialVector(0., 0., 0., 1., 0., 0.);
295  mJointAxes[1] = Math::SpatialVector(0., 0., 0., 0., 1., 0.);
296  mJointAxes[2] = Math::SpatialVector(0., 0., 0., 0., 0., 1.);
297  }
298  else if ((type >= JointType1DoF) && (type <= JointType6DoF))
299  {
300  // create a joint and allocate memory for it.
301  // Warning: the memory does not get initialized by this function!
302  mDoFCount = type - JointType1DoF + 1;
304  }
305  else if (type == JointTypeCustom)
306  {
307  // This constructor cannot be used for a JointTypeCustom because
308  // we have no idea what mDoFCount is.
309  throw RdlException("Error: Invalid use of Joint constructor Joint(JointType type). Only allowed when type != JointTypeCustom");
310  }
311  else if ((type != JointTypeFixed) && (type != JointTypeFloatingBase))
312  {
313  throw RdlException("Error: Invalid use of Joint constructor Joint(JointType type).");
314  }
315  }
316 
317  Joint(JointType type, int degreesOfFreedom) : mJointAxes(nullptr), mJointType(type), mDoFCount(0), q_index(0), custom_joint_index(-1)
318  {
319  if (type == JointTypeCustom)
320  {
321  mDoFCount = degreesOfFreedom;
323 
324  for (unsigned int i = 0; i < mDoFCount; ++i)
325  {
326  mJointAxes[i] = Math::SpatialVector(0., 0., 0., 0., 0., 0.);
327  }
328  }
329  else
330  {
331  throw RdlException("Error: Invalid use of Joint constructor Joint(JointType type, int degreesOfFreedom). Only allowed when type == JointTypeCustom.");
332  }
333  }
334 
336  {
338 
339  for (unsigned int i = 0; i < mDoFCount; i++)
340  {
341  mJointAxes[i] = joint.mJointAxes[i];
342  }
343  }
344 
345  Joint& operator=(const Joint& joint)
346  {
347  if (this != &joint)
348  {
349  if (mDoFCount > 0)
350  {
351  assert(mJointAxes);
352  delete[] mJointAxes;
353  }
354  mJointType = joint.mJointType;
355  mDoFCount = joint.mDoFCount;
358 
359  for (unsigned int i = 0; i < mDoFCount; i++)
360  {
361  mJointAxes[i] = joint.mJointAxes[i];
362  }
363 
364  q_index = joint.q_index;
365  }
366  return *this;
367  }
368 
370  {
371  if (mJointAxes)
372  {
373  assert(mJointAxes);
374  delete[] mJointAxes;
375  mJointAxes = nullptr;
376  mDoFCount = 0;
377  custom_joint_index = -1;
378  }
379  }
380 
389  Joint(const JointType joint_type, const Math::Vector3d& joint_axis) : mDoFCount(1), q_index(0), custom_joint_index(-1)
390  {
392 
393  // Some assertions, as we concentrate on simple cases
394 
395  // Only rotation around the Z-axis
396  assert(joint_type == JointTypeRevolute || joint_type == JointTypePrismatic);
397 
398  mJointType = joint_type;
399 
400  if (joint_type == JointTypeRevolute)
401  {
402  // make sure we have a unit axis
403  mJointAxes[0].set(joint_axis[0], joint_axis[1], joint_axis[2], 0., 0., 0.);
404  }
405  else if (joint_type == JointTypePrismatic)
406  {
407  // make sure we have a unit axis
408  assert(joint_axis.squaredNorm() == 1.);
409 
410  mJointAxes[0].set(0., 0., 0., joint_axis[0], joint_axis[1], joint_axis[2]);
411  }
412  }
413 
423  explicit Joint(const Math::SpatialVector& axis_0) : mDoFCount(1), q_index(0), custom_joint_index(-1)
424  {
426  mJointAxes[0] = Math::SpatialVector(axis_0);
427 
428  if (axis_0 == Math::SpatialVector(1., 0., 0., 0., 0., 0.))
429  {
431  }
432  else if (axis_0 == Math::SpatialVector(0., 1., 0., 0., 0., 0.))
433  {
435  }
436  else if (axis_0 == Math::SpatialVector(0., 0., 1., 0., 0., 0.))
437  {
439  }
440  else
441  {
443  }
445  }
446 
458  {
460  mJointAxes[0] = axis_0;
461  mJointAxes[1] = axis_1;
462 
465  }
466 
478  Joint(const Math::SpatialVector& axis_0, const Math::SpatialVector& axis_1, const Math::SpatialVector& axis_2)
480  {
482 
483  mJointAxes[0] = axis_0;
484  mJointAxes[1] = axis_1;
485  mJointAxes[2] = axis_2;
486 
490  }
491 
504  Joint(const Math::SpatialVector& axis_0, const Math::SpatialVector& axis_1, const Math::SpatialVector& axis_2, const Math::SpatialVector& axis_3)
506  {
508 
509  mJointAxes[0] = axis_0;
510  mJointAxes[1] = axis_1;
511  mJointAxes[2] = axis_2;
512  mJointAxes[3] = axis_3;
513 
518  }
519 
533  Joint(const Math::SpatialVector& axis_0, const Math::SpatialVector& axis_1, const Math::SpatialVector& axis_2, const Math::SpatialVector& axis_3,
534  const Math::SpatialVector& axis_4)
536  {
538 
539  mJointAxes[0] = axis_0;
540  mJointAxes[1] = axis_1;
541  mJointAxes[2] = axis_2;
542  mJointAxes[3] = axis_3;
543  mJointAxes[4] = axis_4;
544 
550  }
551 
566  Joint(const Math::SpatialVector& axis_0, const Math::SpatialVector& axis_1, const Math::SpatialVector& axis_2, const Math::SpatialVector& axis_3,
567  const Math::SpatialVector& axis_4, const Math::SpatialVector& axis_5)
569  {
571 
572  mJointAxes[0] = axis_0;
573  mJointAxes[1] = axis_1;
574  mJointAxes[2] = axis_2;
575  mJointAxes[3] = axis_3;
576  mJointAxes[4] = axis_4;
577  mJointAxes[5] = axis_5;
578 
585  }
586 
593  {
594  if (fabs(axis.norm() - 1.0) > 1.0e-8)
595  {
596  std::cerr << "Warning: joint axis is not unit!" << std::endl;
597  }
598 
599  bool axis_rotational = false;
600  bool axis_translational = false;
601 
602  Math::Vector3d rotation(axis[0], axis[1], axis[2]);
603  Math::Vector3d translation(axis[3], axis[4], axis[5]);
604 
605  if (fabs(translation.norm()) < 1.0e-8)
606  {
607  axis_rotational = true;
608  }
609 
610  if (fabs(rotation.norm()) < 1.0e-8)
611  {
612  axis_translational = true;
613  }
614 
615  return axis_rotational || axis_translational;
616  }
617 
620 
623 
625  // have here a value of 0 and their actual numbers of degrees of freedom
626  // can be obtained using the CustomJoint structure.
627  unsigned int mDoFCount;
628  unsigned int q_index;
629  unsigned int custom_joint_index;
630 };
631 
644 void jcalc(Model& model, unsigned int joint_id, const Math::VectorNd& q, const Math::VectorNd& qdot);
645 
646 Math::SpatialTransform jcalc_XJ(Model& model, unsigned int joint_id, const Math::VectorNd& q);
647 
648 void jcalc_X_lambda_S(Model& model, unsigned int joint_id, const Math::VectorNd& q);
649 
657 {
662  {
663  }
664 
668  virtual ~CustomJoint()
669  {
670  }
671 
678  virtual void jcalc(Model& model, unsigned int joint_id, const Math::VectorNd& q, const Math::VectorNd& qdot) = 0;
679 
680  virtual void jcalc_X_lambda_S(Model& model, unsigned int joint_id, const Math::VectorNd& q) = 0;
681 
682  unsigned int mDoFCount;
691 };
692 } // namespace RobotDynamics
693 
694 /* RDL_JOINT_H */
695 #endif // ifndef __RDL_JOINT_H__
Definition: rdl_eigenmath.hpp:187
EIGEN_STRONG_INLINE void set(const double &v0, const double &v1, const double &v2, const double &v3, const double &v4, const double &v5)
Definition: rdl_eigenmath.hpp:223
Definition: rdl_eigenmath.hpp:54
A custom exception.
Definition: RdlExceptions.hpp:18
Eigen::VectorXd VectorNd
Definition: rdl_eigenmath.hpp:20
Eigen::MatrixXd MatrixNd
Definition: rdl_eigenmath.hpp:21
Namespace for all structures of the RobotDynamics library.
Definition: examples.hpp:19
Math::SpatialTransform jcalc_XJ(Model &model, unsigned int joint_id, const Math::VectorNd &q)
Definition: Joint.cpp:212
void jcalc(Model &model, unsigned int joint_id, const VectorNd &q, const VectorNd &qdot)
Computes all variables for a joint model and updates the body frame as well as the body's center of m...
Definition: Joint.cpp:17
JointType
General types of joints.
Definition: Joint.hpp:182
@ JointTypeSpherical
3 DoF joint using Quaternions for joint positional variables and
Definition: Joint.hpp:189
@ JointTypeRevoluteX
Definition: Joint.hpp:186
@ JointTypeCustom
User defined joints of varying size.
Definition: Joint.hpp:207
@ JointTypeFixed
Fixed joint which causes the inertial properties to be merged with.
Definition: Joint.hpp:199
@ JointTypeEulerXYZ
3 DoF joint that uses Euler XYZ convention (faster than emulated
Definition: Joint.hpp:193
@ JointType4DoF
Emulated 4 DoF joint.
Definition: Joint.hpp:204
@ JointTypeRevoluteY
Definition: Joint.hpp:187
@ JointTypeRevoluteZ
Definition: Joint.hpp:188
@ JointTypeTranslationXYZ
Definition: Joint.hpp:197
@ JointType6DoF
Emulated 6 DoF joint.
Definition: Joint.hpp:206
@ JointTypeUndefined
Definition: Joint.hpp:183
@ JointTypeEulerYXZ
3 DoF joint that uses Euler YXZ convention (faster than emulated
Definition: Joint.hpp:195
@ JointTypeEulerZYX
3 DoF joint that uses Euler ZYX convention (faster than emulated
Definition: Joint.hpp:191
@ JointType2DoF
Emulated 2 DoF joint.
Definition: Joint.hpp:202
@ JointType5DoF
Emulated 5 DoF joint.
Definition: Joint.hpp:205
@ JointTypeRevolute
Definition: Joint.hpp:184
@ JointType1DoF
Definition: Joint.hpp:201
@ JointTypePrismatic
Definition: Joint.hpp:185
@ JointType3DoF
Emulated 3 DoF joint.
Definition: Joint.hpp:203
@ JointTypeFloatingBase
A 6-DoF joint for floating-base (or freeflyer) systems.
Definition: Joint.hpp:198
void jcalc_X_lambda_S(Model &model, unsigned int joint_id, const VectorNd &q)
Definition: Joint.cpp:242
CustomJoint is a struct used to create a joint with user defined parameters. This is accomplished by ...
Definition: Joint.hpp:657
Math::MatrixNd S_o
Definition: Joint.hpp:685
Math::MatrixNd S
Definition: Joint.hpp:684
Math::SpatialTransform XJ
Definition: Joint.hpp:683
Math::VectorNd d_u
Definition: Joint.hpp:689
virtual ~CustomJoint()
Destructor.
Definition: Joint.hpp:668
virtual void jcalc(Model &model, unsigned int joint_id, const Math::VectorNd &q, const Math::VectorNd &qdot)=0
CustomJoint()
Constructor.
Definition: Joint.hpp:661
Math::VectorNd ndof0_vec
Definition: Joint.hpp:690
Math::MatrixNd U
Definition: Joint.hpp:686
Math::VectorNd u
Definition: Joint.hpp:688
virtual void jcalc_X_lambda_S(Model &model, unsigned int joint_id, const Math::VectorNd &q)=0
Math::MatrixNd Dinv
Definition: Joint.hpp:687
unsigned int mDoFCount
Definition: Joint.hpp:682
Describes a joint relative to the predecessor body.
Definition: Joint.hpp:223
unsigned int q_index
Definition: Joint.hpp:628
unsigned int custom_joint_index
Definition: Joint.hpp:629
Joint(const Math::SpatialVector &axis_0, const Math::SpatialVector &axis_1, const Math::SpatialVector &axis_2)
Constructs a 3 DoF joint with the given motion subspaces.
Definition: Joint.hpp:478
Joint(JointType type)
Definition: Joint.hpp:228
Joint(const Math::SpatialVector &axis_0, const Math::SpatialVector &axis_1, const Math::SpatialVector &axis_2, const Math::SpatialVector &axis_3, const Math::SpatialVector &axis_4)
Constructs a 5 DoF joint with the given motion subspaces.
Definition: Joint.hpp:533
JointType mJointType
Type of joint.
Definition: Joint.hpp:622
Joint()
Definition: Joint.hpp:224
~Joint()
Definition: Joint.hpp:369
Joint(const Math::SpatialVector &axis_0, const Math::SpatialVector &axis_1, const Math::SpatialVector &axis_2, const Math::SpatialVector &axis_3)
Constructs a 4 DoF joint with the given motion subspaces.
Definition: Joint.hpp:504
Joint(const Math::SpatialVector &axis_0, const Math::SpatialVector &axis_1, const Math::SpatialVector &axis_2, const Math::SpatialVector &axis_3, const Math::SpatialVector &axis_4, const Math::SpatialVector &axis_5)
Constructs a 6 DoF joint with the given motion subspaces.
Definition: Joint.hpp:566
unsigned int mDoFCount
Number of degrees of freedom of the joint. Note: CustomJoints.
Definition: Joint.hpp:627
Joint(const JointType joint_type, const Math::Vector3d &joint_axis)
Constructs a joint from the given cartesian parameters.
Definition: Joint.hpp:389
bool validate_spatial_axis(Math::SpatialVector &axis)
Checks whether we have pure rotational or translational axis.
Definition: Joint.hpp:592
Joint(JointType type, int degreesOfFreedom)
Definition: Joint.hpp:317
Joint & operator=(const Joint &joint)
Definition: Joint.hpp:345
Joint(const Math::SpatialVector &axis_0)
Constructs a 1 DoF joint with the given motion subspaces.
Definition: Joint.hpp:423
Joint(const Joint &joint)
Definition: Joint.hpp:335
Joint(const Math::SpatialVector &axis_0, const Math::SpatialVector &axis_1)
Constructs a 2 DoF joint with the given motion subspaces.
Definition: Joint.hpp:457
Math::SpatialVector * mJointAxes
The spatial axes of the joint.
Definition: Joint.hpp:619
Compact representation of spatial transformations.
Definition: rdl_eigenmath.hpp:412
Contains all information about the rigid body model.
Definition: Model.hpp:112