rigid-body-kinematics.hpp
Go to the documentation of this file.
1 
13 #ifndef StATEOBSERVATIONRIGIDBODYKINEMATICS_H
14 #define StATEOBSERVATIONRIGIDBODYKINEMATICS_H
15 
16 #include <Eigen/SVD>
17 
18 #include <state-observation/api.h>
22 
23 namespace stateObservation
24 {
25 namespace kine
26 {
27 inline void integrateKinematics(Vector3 & position, const Vector3 & velocity, double dt);
28 
29 inline void integrateKinematics(Vector3 & position, Vector3 & velocity, const Vector3 & acceleration, double dt);
30 
31 inline void integrateKinematics(Matrix3 & orientation, const Vector3 & rotationVelocity, double dt);
32 
33 inline void integrateKinematics(Matrix3 & orientation,
34  Vector3 & rotationVelocity,
35  const Vector3 & rotationAcceleration,
36  double dt);
37 
38 inline void integrateKinematics(Quaternion & orientation, const Vector3 & rotationVelocity, double dt);
39 
40 inline void integrateKinematics(Quaternion & orientation,
41  Vector3 & rotationVelocity,
42  const Vector3 & rotationAcceleration,
43  double dt);
44 
48 inline void integrateKinematics(Vector3 & position,
49  Vector3 & velocity,
50  const Vector3 & acceleration,
51  Matrix3 & orientation,
52  Vector3 & rotationVelocity,
53  const Vector3 & rotationAcceleration,
54  double dt);
55 
59 inline void integrateKinematics(Vector3 & position,
60  Vector3 & velocity,
61  const Vector3 & acceleration,
62  Quaternion & orientation,
63  Vector3 & rotationVelocity,
64  const Vector3 & rotationAcceleration,
65  double dt);
66 
68 inline void integrateKinematics(Vector3 & position,
69  const Vector3 & velocity,
70  Matrix3 & orientation,
71  const Vector3 & rotationVelocity,
72  double dt);
73 
75 inline void integrateKinematics(Vector3 & position,
76  const Vector3 & velocity,
77  Quaternion & orientation,
78  const Vector3 & rotationVelocity,
79  double dt);
80 
83 inline Vector regulateRotationVector(const Vector3 & v);
84 
87 
90 
93 
96 
99 
101 inline Vector3 quaternionToRotationVector(const Vector4 & v);
102 
104 inline double scalarComponent(const Quaternion & q);
105 
107 inline Vector3 vectorComponent(const Quaternion & q);
108 
111 inline Vector3 rotationMatrixToRollPitchYaw(const Matrix3 & R, Vector3 & v);
112 
114 
117 inline Matrix3 rollPitchYawToRotationMatrix(double roll, double pitch, double yaw);
118 
119 inline Matrix3 rollPitchYawToRotationMatrix(const Vector3 & rpy);
120 
123 inline Quaternion rollPitchYawToQuaternion(double roll, double pitch, double yaw);
124 
125 inline Quaternion rollPitchYawToQuaternion(const Vector3 & rpy);
126 
129 
131 inline Matrix3 skewSymmetric(const Vector3 & v, Matrix3 & R);
132 
134 inline Matrix3 skewSymmetric(const Vector3 & v);
135 
137 inline Matrix3 skewSymmetric2(const Vector3 & v, Matrix3 & R);
138 
140 inline Matrix3 skewSymmetric2(const Vector3 & v);
141 
143 inline Vector6 homogeneousMatrixToVector6(const Matrix4 & M);
144 
146 inline Matrix4 vector6ToHomogeneousMatrix(const Vector6 & v);
147 
154 inline Matrix3 twoVectorsToRotationMatrix(const Vector3 & v1, const Vector3 Rv1);
155 
161 inline bool isPureYaw(const Matrix3 & R);
162 
170 
179 inline Vector3 getInvariantOrthogonalVector(const Matrix3 & Rhat, const Vector3 & Rtez);
180 
190 inline Matrix3 mergeTiltWithYaw(const Vector3 & Rtez,
191  const Matrix3 & R2,
192  const Vector3 & v = Vector3::UnitX()) noexcept(false);
193 
200 inline Matrix3 mergeRoll1Pitch1WithYaw2(const Matrix3 & R1, const Matrix3 & R2, const Vector3 & v = Vector3::UnitX());
201 
208 inline Matrix3 mergeTiltWithYawAxisAgnostic(const Vector3 & Rtez, const Matrix3 & R2);
209 
216 inline Matrix3 mergeRoll1Pitch1WithYaw2AxisAgnostic(const Matrix3 & R1, const Matrix3 & R2);
217 
224 inline double rotationMatrixToAngle(const Matrix3 & rotation, const Vector3 & axis, const Vector3 & v);
225 
233 inline double rotationMatrixToYaw(const Matrix3 & rotation, const Vector2 & v);
234 
238 inline double rotationMatrixToYaw(const Matrix3 & rotation);
239 
246 inline double rotationMatrixToYawAxisAgnostic(const Matrix3 & rotation);
247 
252 
257 
261 inline double randomAngle();
262 
267 inline bool isRotationMatrix(const Matrix3 &, double precision = 2 * cst::epsilon1);
268 
270 inline void fixedPointRotationToTranslation(const Matrix3 & R,
271  const Vector3 & rotationVelocity,
272  const Vector3 & rotationAcceleration,
273  const Vector3 & fixedPoint,
274  Vector3 & outputTranslation,
275  Vector3 & outputLinearVelocity,
276  Vector3 & outputLinearAcceleration);
277 
279 inline Vector3 derivateRotationFD(const Quaternion & q1, const Quaternion & q2, double dt);
280 
282 inline Vector3 derivateRotationFD(const Vector3 & o1, const Vector3 & o2, double dt);
283 
284 inline Vector6 derivateHomogeneousMatrixFD(const Matrix4 & m1, const Matrix4 & m2, double dt);
285 
286 inline Vector6 derivatePoseThetaUFD(const Vector6 & v1, const Vector6 & v2, double dt);
287 
295 inline void derivateRotationMultiplicative(const Vector3 & deltaR, Matrix3 & dRdR, Matrix3 & dRddeltaR);
296 
300 inline Matrix3 derivateRtvMultiplicative(const Matrix3 & R, const Vector3 & v);
301 
304 inline IndexedVectorArray reconstructStateTrajectory(const IndexedVectorArray & positionOrientation, double dt);
305 
306 inline Vector invertState(const Vector & state);
307 
308 inline Matrix4 invertHomoMatrix(const Matrix4 & m);
309 
311 {
312  matrix = 0,
316 };
317 
318 template<rotationType = rotationVector>
319 struct indexes
320 {
321 };
322 
323 template<>
325 {
328  static const Index pos = 0;
329  static const Index ori = 3;
330  static const Index linVel = 6;
331  static const Index angVel = 9;
332  static const Index linAcc = 12;
333  static const Index angAcc = 15;
334  static const Index size = 18;
335 };
336 
337 template<>
339 {
342  static const Index pos = 0;
343  static const Index ori = 3;
344  static const Index linVel = 7;
345  static const Index angVel = 10;
346  static const Index linAcc = 13;
347  static const Index angAcc = 16;
348  static const Index size = 19;
349 };
350 
352 constexpr double quatNormTol = 1e-6;
353 
355 {
356 public:
360  explicit Orientation(bool initialize = true);
361 
363  explicit Orientation(const Vector3 & v);
364 
365  explicit Orientation(const Quaternion & q);
366 
367  explicit Orientation(const Matrix3 & m);
368 
369  explicit Orientation(const AngleAxis & aa);
370 
371  Orientation(const Quaternion & q, const Matrix3 & m);
372 
373  Orientation(const double & roll, const double & pitch, const double & yaw);
374 
375  Orientation(const Orientation & multiplier1, const Orientation & multiplier2);
376 
377  inline Orientation & operator=(const Vector3 & v);
378 
379  inline Orientation & operator=(const Quaternion & q);
380 
381  inline Orientation & operator=(const Matrix3 & m);
382 
383  inline Orientation & operator=(const AngleAxis & aa);
384 
385  inline Orientation & setValue(const Quaternion & q, const Matrix3 & m);
386 
387  inline Orientation & fromVector4(const Vector4 & v);
388 
389  inline Orientation & setRandom();
390 
391  template<typename t = Quaternion>
392  inline Orientation & setZeroRotation();
393 
395  inline const Matrix3 & toMatrix3() const;
396  inline const Quaternion & toQuaternion() const;
397 
398  inline operator const Matrix3 &() const;
399  inline operator const Quaternion &() const;
400 
401  inline Vector4 toVector4() const;
402 
403  inline Vector3 toRotationVector() const;
404  inline Vector3 toRollPitchYaw() const;
405  inline AngleAxis toAngleAxis() const;
406 
409 
410  inline Orientation operator*(const Orientation & R2) const;
411 
413  inline const Orientation & setToProductNoAlias(const Orientation & R1, const Orientation & R2);
414 
415  inline Orientation inverse() const;
416 
421  inline const Orientation & integrate(Vector3 dt_x_omega);
422 
425  inline const Orientation & integrateRightSide(Vector3 dt_x_omega);
426 
434  inline Vector3 differentiate(Orientation R_k1) const;
435 
443  inline Vector3 differentiateRightSide(Orientation R_k1) const;
444 
446  inline Vector3 operator*(const Vector3 & v) const;
447 
450  inline bool isSet() const;
451 
454  inline void reset();
455 
458  inline bool isMatrixSet() const;
461  inline bool isQuaternionSet() const;
462 
465  inline void setMatrix(bool b = true);
466  inline void setQuaternion(bool b = true);
467 
469 
478 
480  inline void synchronize();
481 
483  static inline Orientation zeroRotation();
484 
486  static inline Orientation randomRotation();
487 
488  EIGEN_MAKE_ALIGNED_OPERATOR_NEW
489 
490 protected:
491  void check_() const;
492 
493  inline const Matrix3 & quaternionToMatrix_() const;
494  inline const Quaternion & matrixToQuaternion_() const;
495 
498 };
499 
500 namespace internal
501 {
502 
503 template<class T>
505 {
506 public:
508 
517  const CheckedVector3 & linVel,
518  const CheckedVector3 & linAcc,
519  const Orientation & orientation,
520  const CheckedVector3 & angVel,
521  const CheckedVector3 & angAcc);
522  struct Flags
523  {
524  typedef unsigned char Byte;
525 
526  static const Byte position = BOOST_BINARY(000001);
527  static const Byte orientation = BOOST_BINARY(000010);
528  static const Byte linVel = BOOST_BINARY(000100);
529  static const Byte angVel = BOOST_BINARY(001000);
530  static const Byte linAcc = BOOST_BINARY(010000);
531  static const Byte angAcc = BOOST_BINARY(100000);
532 
533  static const Byte pose = position | orientation;
534  static const Byte vel = linVel | angVel;
535  static const Byte acc = linAcc | angAcc;
536  static const Byte all = pose | vel | acc;
537  };
538 
541 
544 
547 
548  inline void reset();
549 
555  T & fromVector(const Vector & v, typename Flags::Byte = Flags::all);
556 
560  template<typename t = Quaternion>
561  T & setZero(typename Flags::Byte = Flags::all);
562 
566  static inline T zeroKinematics(typename Flags::Byte = Flags::all);
567 
572  inline Vector toVector(typename Flags::Byte) const;
573  inline Vector toVector() const;
574 };
575 } // namespace internal
576 
577 struct LocalKinematics;
578 
584 struct Kinematics : public internal::KinematicsInternal<Kinematics>
585 {
586 
588 
594  Kinematics(const Vector & v, Flags::Byte = Flags::all);
595 
599  Kinematics(const Kinematics & multiplier1, const Kinematics & multiplier2);
600 
609  const CheckedVector3 & linVel,
610  const CheckedVector3 & linAcc,
611  const Orientation & orientation,
612  const CheckedVector3 & angVel,
613  const CheckedVector3 & angAcc);
614 
618  explicit inline Kinematics(const LocalKinematics & locK);
619 
623  inline Kinematics & operator=(const LocalKinematics & locK);
624 
629  inline const Kinematics & integrate(double dt);
630 
639  inline const Kinematics & update(const Kinematics & newValue, double dt, Flags::Byte = Flags::all);
640 
645  inline Kinematics getInverse() const;
646 
648  inline Kinematics operator*(const Kinematics &) const;
649 
654  inline Kinematics & setToProductNoAlias(const Kinematics & operand1, const Kinematics & operand2);
655 
658  inline Kinematics & setToDiffNoAlias(const Kinematics & multiplier1, const Kinematics & multiplier2);
659 
661  inline Kinematics & setToDiffNoAliasLinPart(const Kinematics & multiplier1, const Kinematics & multiplier2);
662 
664  inline Kinematics & setToDiffNoAliasAngPart(const Kinematics & multiplier1, const Kinematics & multiplier2);
665 
666  EIGEN_MAKE_ALIGNED_OPERATOR_NEW
667 
668 protected:
670 };
671 
677 struct LocalKinematics : public internal::KinematicsInternal<LocalKinematics>
678 {
680 
686  inline LocalKinematics(const Vector & v, Flags::Byte flags);
687 
691  inline LocalKinematics(const LocalKinematics & multiplier1, const LocalKinematics & multiplier2);
692 
701  const CheckedVector3 & linVel,
702  const CheckedVector3 & linAcc,
703  const Orientation & orientation,
704  const CheckedVector3 & angVel,
705  const CheckedVector3 & angAcc);
706 
710  explicit inline LocalKinematics(const Kinematics & kin);
711 
715  inline LocalKinematics & operator=(const Kinematics & kine);
716 
720  template<typename t = Quaternion>
721  LocalKinematics & setZero(Flags::Byte = Flags::all);
722 
727  inline const LocalKinematics & integrate(double dt);
728 
737  inline const LocalKinematics & update(const LocalKinematics & newValue, double dt, Flags::Byte = Flags::all);
738 
743  inline LocalKinematics getInverse() const;
744 
746  inline LocalKinematics operator*(const LocalKinematics &) const;
747 
752  inline LocalKinematics & setToProductNoAlias(const LocalKinematics & operand1, const LocalKinematics & operand2);
753 
756  inline LocalKinematics & setToDiffNoAlias(const LocalKinematics & multiplier1, const LocalKinematics & multiplier2);
757 
759  inline LocalKinematics & setToDiffNoAliasLinPart(const LocalKinematics & multiplier1,
760  const LocalKinematics & multiplier2);
761 
763  inline LocalKinematics & setToDiffNoAliasAngPart(const LocalKinematics & multiplier1,
764  const LocalKinematics & multiplier2);
765  EIGEN_MAKE_ALIGNED_OPERATOR_NEW
766 
767 protected:
773 };
774 
775 } // namespace kine
776 } // namespace stateObservation
777 
778 inline std::ostream & operator<<(std::ostream & os, const stateObservation::kine::Kinematics & k);
779 
780 inline std::ostream & operator<<(std::ostream & os, const stateObservation::kine::LocalKinematics & k);
781 
782 #include <state-observation/tools/rigid-body-kinematics.hxx>
783 
784 #endif // StATEOBSERVATIONRIGIDBODYKINEMATICS_H
stateObservation::Vector
Eigen::VectorXd Vector
Dynamic sized scalar vector.
Definition: definitions.hpp:76
probability-law-simulation.hpp
stateObservation::kine::LocalKinematics::integrate
const LocalKinematics & integrate(double dt)
integrates the current local kinematics over the timestep dt.
stateObservation::kine::Kinematics::Kinematics
Kinematics()
Definition: rigid-body-kinematics.hpp:587
stateObservation::kine::angleaxis
@ angleaxis
Definition: rigid-body-kinematics.hpp:315
stateObservation::kine::internal::KinematicsInternal::reset
void reset()
stateObservation::kine::quatNormTol
constexpr double quatNormTol
relative tolereance to the square of quaternion norm.
Definition: rigid-body-kinematics.hpp:352
stateObservation::kine::regulateRotationVector
Vector regulateRotationVector(const Vector3 &v)
stateObservation::Matrix4
Eigen::Matrix4d Matrix4
4x4 Scalar Matrix
Definition: definitions.hpp:115
stateObservation::kine::Orientation::toRollPitchYaw
Vector3 toRollPitchYaw() const
stateObservation::kine::internal::KinematicsInternal::Flags::linAcc
static const Byte linAcc
Definition: rigid-body-kinematics.hpp:530
stateObservation::kine::Kinematics::operator*
Kinematics operator*(const Kinematics &) const
composition of transformation
stateObservation::kine::internal::KinematicsInternal::Flags::acc
static const Byte acc
Definition: rigid-body-kinematics.hpp:535
stateObservation::kine::twoVectorsToRotationMatrix
Matrix3 twoVectorsToRotationMatrix(const Vector3 &v1, const Vector3 Rv1)
Builds the smallest angle matrix allowing to get from a NORMALIZED vector v1 to its imahe Rv1 This is...
stateObservation::kine::rollPitchYawToRotationMatrix
Matrix3 rollPitchYawToRotationMatrix(double roll, double pitch, double yaw)
stateObservation::kine::randomRotationQuaternion
Quaternion randomRotationQuaternion()
Get a uniformly random Quaternion.
stateObservation::kine::Orientation::m_
CheckedMatrix3 m_
Definition: rigid-body-kinematics.hpp:497
stateObservation::kine::internal::KinematicsInternal::position
CheckedVector3 position
Definition: rigid-body-kinematics.hpp:539
stateObservation::kine::internal::KinematicsInternal::zeroKinematics
static T zeroKinematics(typename Flags::Byte=Flags::all)
returns an object corresponding to zero kinematics on the desired variables.
stateObservation::kine::Orientation::inverse
Orientation inverse() const
stateObservation::kine::Orientation::setToProductNoAlias
const Orientation & setToProductNoAlias(const Orientation &R1, const Orientation &R2)
Noalias versions of the operator*.
stateObservation::kine::LocalKinematics::tempVec_5
Vector3 tempVec_5
Definition: rigid-body-kinematics.hpp:772
stateObservation::kine::Orientation::Orientation
Orientation(bool initialize=true)
stateObservation::Vector2
Eigen::Matrix< double, 2, 1 > Vector2
2d Vector
Definition: definitions.hpp:82
stateObservation::kine::Orientation::toVector4
Vector4 toVector4() const
stateObservation::kine::rotationVectorToAngleAxis
AngleAxis rotationVectorToAngleAxis(const Vector3 &v)
Transforms the rotation vector into angle axis.
stateObservation::kine::rotationVectorToRotationMatrix
Matrix3 rotationVectorToRotationMatrix(const Vector3 &v)
Transforms the rotation vector into rotation matrix.
stateObservation::kine::indexes
Definition: rigid-body-kinematics.hpp:319
stateObservation::kine::LocalKinematics::tempVec_3
Vector3 tempVec_3
Definition: rigid-body-kinematics.hpp:770
stateObservation::kine::skewSymmetric2
Matrix3 skewSymmetric2(const Vector3 &v, Matrix3 &R)
transform a 3d vector into a squared skew symmetric 3x3 matrix
stateObservation::kine::skewSymmetric
Matrix3 skewSymmetric(const Vector3 &v, Matrix3 &R)
transform a 3d vector into a skew symmetric 3x3 matrix
stateObservation::kine::internal::KinematicsInternal::Flags::vel
static const Byte vel
Definition: rigid-body-kinematics.hpp:534
stateObservation::kine::internal::KinematicsInternal::Flags
Definition: rigid-body-kinematics.hpp:522
stateObservation::kine::mergeRoll1Pitch1WithYaw2AxisAgnostic
Matrix3 mergeRoll1Pitch1WithYaw2AxisAgnostic(const Matrix3 &R1, const Matrix3 &R2)
Merge the roll and pitch with the yaw from a rotation matrix with optimal reference vector.
stateObservation::kine::getInvariantHorizontalVector
Vector3 getInvariantHorizontalVector(const Matrix3 &R)
Gets a vector that remains horizontal with this rotation. This vector is NOT normalized.
stateObservation::kine::LocalKinematics::LocalKinematics
LocalKinematics()
Definition: rigid-body-kinematics.hpp:679
stateObservation::kine::Orientation::integrateRightSide
const Orientation & integrateRightSide(Vector3 dt_x_omega)
stateObservation::kine::internal::KinematicsInternal::Flags::linVel
static const Byte linVel
Definition: rigid-body-kinematics.hpp:528
stateObservation::kine::internal::KinematicsInternal::fromVector
T & fromVector(const Vector &v, typename Flags::Byte=Flags::all)
stateObservation::kine::Orientation::operator=
Orientation & operator=(const Vector3 &v)
stateObservation::IndexedMatrixArrayT< Vector >
stateObservation::kine::isPureYaw
bool isPureYaw(const Matrix3 &R)
checks if this matrix is a pure yaw matrix or not
stateObservation::kine::internal::KinematicsInternal::linAcc
CheckedVector3 linAcc
Definition: rigid-body-kinematics.hpp:545
stateObservation::kine::reconstructStateTrajectory
IndexedVectorArray reconstructStateTrajectory(const IndexedVectorArray &positionOrientation, double dt)
stateObservation::kine::mergeRoll1Pitch1WithYaw2
Matrix3 mergeRoll1Pitch1WithYaw2(const Matrix3 &R1, const Matrix3 &R2, const Vector3 &v=Vector3::UnitX())
Merge the roll and pitch with the yaw from a rotation matrix (minimizes the deviation of the v vector...
stateObservation::kine::Orientation::toRotationVector
Vector3 toRotationVector() const
stateObservation::kine::Kinematics
Class facilitating the manipulation of the kinematics of a frame within another and the associated op...
Definition: rigid-body-kinematics.hpp:584
stateObservation::kine::LocalKinematics::update
const LocalKinematics & update(const LocalKinematics &newValue, double dt, Flags::Byte=Flags::all)
updates the current local kinematics (k) with the new ones (k+1).
stateObservation::kine::LocalKinematics::setToDiffNoAliasAngPart
LocalKinematics & setToDiffNoAliasAngPart(const LocalKinematics &multiplier1, const LocalKinematics &multiplier2)
Angular part of the setToDiffNoAlias(const LocalKinematics &, const LocalKinematics &) function.
stateObservation::kine::Orientation::synchronize
void synchronize()
synchronizes the representations (quaternion and rotation matrix)
stateObservation::kine::rotationMatrixToYawAxisAgnostic
double rotationMatrixToYawAxisAgnostic(const Matrix3 &rotation)
take 3x3 matrix represeting a rotation and gives a corresponding angle around upward vertical axis
stateObservation::kine::fixedPointRotationToTranslation
void fixedPointRotationToTranslation(const Matrix3 &R, const Vector3 &rotationVelocity, const Vector3 &rotationAcceleration, const Vector3 &fixedPoint, Vector3 &outputTranslation, Vector3 &outputLinearVelocity, Vector3 &outputLinearAcceleration)
transforms a rotation into translation given a constraint of a fixed point
stateObservation::kine::Orientation::differentiateRightSide
Vector3 differentiateRightSide(Orientation R_k1) const
gives the log (rotation vector) of the "right-side" difference of orientation: log of (*this)....
stateObservation::kine::Orientation::toMatrix3
const Matrix3 & toMatrix3() const
get a const reference on the matrix or the quaternion
stateObservation::kine::internal::KinematicsInternal::Flags::position
static const Byte position
Definition: rigid-body-kinematics.hpp:526
stateObservation::kine::Orientation::setRandom
Orientation & setRandom()
stateObservation::kine::rotationType
rotationType
Definition: rigid-body-kinematics.hpp:310
stateObservation::kine::Orientation::integrate
const Orientation & integrate(Vector3 dt_x_omega)
stateObservation::kine::Kinematics::setToDiffNoAliasAngPart
Kinematics & setToDiffNoAliasAngPart(const Kinematics &multiplier1, const Kinematics &multiplier2)
Angular part of the setToDiffNoAlias(const Kinematics &, const Kinematics &) function.
stateObservation::kine::LocalKinematics::operator*
LocalKinematics operator*(const LocalKinematics &) const
composition of transformation
stateObservation::kine::rotationMatrixToYaw
double rotationMatrixToYaw(const Matrix3 &rotation, const Vector2 &v)
take 3x3 matrix represeting a rotation and gives the angle that vector v turns around the upward vert...
stateObservation::kine::Kinematics::setToProductNoAlias
Kinematics & setToProductNoAlias(const Kinematics &operand1, const Kinematics &operand2)
computes the composition of two Kinematics object.
stateObservation::kine::derivateRotationMultiplicative
void derivateRotationMultiplicative(const Vector3 &deltaR, Matrix3 &dRdR, Matrix3 &dRddeltaR)
stateObservation::kine::rotationVectorToQuaternion
Quaternion rotationVectorToQuaternion(const Vector3 &v)
Transforms the rotation vector into quaternion.
stateObservation::kine::rotationMatrixToAngle
double rotationMatrixToAngle(const Matrix3 &rotation, const Vector3 &axis, const Vector3 &v)
take 3x3 matrix represeting a rotation and gives the angle that vector v turns around the axis with t...
stateObservation::kine::LocalKinematics
Class facilitating the manipulation of the local kinematics of a frame within another and the associa...
Definition: rigid-body-kinematics.hpp:677
stateObservation::kine::derivateHomogeneousMatrixFD
Vector6 derivateHomogeneousMatrixFD(const Matrix4 &m1, const Matrix4 &m2, double dt)
stateObservation::kine::invertHomoMatrix
Matrix4 invertHomoMatrix(const Matrix4 &m)
stateObservation::kine::Orientation::matrixToQuaternion_
const Quaternion & matrixToQuaternion_() const
stateObservation::kine::randomAngle
double randomAngle()
get a randomAngle between -pi and pu
stateObservation::kine::mergeTiltWithYawAxisAgnostic
Matrix3 mergeTiltWithYawAxisAgnostic(const Vector3 &Rtez, const Matrix3 &R2)
Merge the roll and pitch from the tilt (R^T e_z) with the yaw from a rotation matrix (minimizes the d...
stateObservation::kine::Orientation::setValue
Orientation & setValue(const Quaternion &q, const Matrix3 &m)
stateObservation::kine::Orientation::operator*
Orientation operator*(const Orientation &R2) const
stateObservation::Matrix3
Eigen::Matrix3d Matrix3
3x3 Scalar Matrix
Definition: definitions.hpp:109
stateObservation::kine::internal::KinematicsInternal::Flags::pose
static const Byte pose
Definition: rigid-body-kinematics.hpp:533
stateObservation::kine::LocalKinematics::tempVec_4
Vector3 tempVec_4
Definition: rigid-body-kinematics.hpp:771
stateObservation::kine::LocalKinematics::getInverse
LocalKinematics getInverse() const
returns the inverse of the current local kinematics.
stateObservation::kine::Orientation::q_
CheckedQuaternion q_
Definition: rigid-body-kinematics.hpp:496
stateObservation::kine::internal::KinematicsInternal::Flags::all
static const Byte all
Definition: rigid-body-kinematics.hpp:536
stateObservation::kine::Kinematics::setToDiffNoAlias
Kinematics & setToDiffNoAlias(const Kinematics &multiplier1, const Kinematics &multiplier2)
stateObservation::kine::Orientation::isSet
bool isSet() const
checks that the orientation has been assigned a value.
stateObservation::hrp2::m
constexpr double m
mass of the robot
Definition: hrp2.hpp:36
stateObservation::kine::invertState
Vector invertState(const Vector &state)
stateObservation::kine::LocalKinematics::setZero
LocalKinematics & setZero(Flags::Byte=Flags::all)
stateObservation::kine::internal::KinematicsInternal::toVector
Vector toVector() const
stateObservation::kine::rotationVector
@ rotationVector
Definition: rigid-body-kinematics.hpp:313
stateObservation::kine::derivateRotationFD
Vector3 derivateRotationFD(const Quaternion &q1, const Quaternion &q2, double dt)
derivates a quaternion using finite difference to get a angular velocity vector
stateObservation::kine::Orientation::check_
void check_() const
stateObservation::kine::isRotationMatrix
bool isRotationMatrix(const Matrix3 &, double precision=2 *cst::epsilon1)
Checks if it is a rotation matrix (right-hand orthonormal) or not.
stateObservation::kine::internal::KinematicsInternal::setZero
T & setZero(typename Flags::Byte=Flags::all)
stateObservation::Vector6
Eigen::Matrix< double, 6, 1 > Vector6
6D vector
Definition: definitions.hpp:97
stateObservation::Index
Eigen::Index Index
Definition: definitions.hpp:138
stateObservation::kine::getInvariantOrthogonalVector
Vector3 getInvariantOrthogonalVector(const Matrix3 &Rhat, const Vector3 &Rtez)
Gets a vector that is orthogonal to and such that is orthogonal to the tilt . This vector is NOT n...
stateObservation::kine::Orientation::toQuaternion
const Quaternion & toQuaternion() const
definitions.hpp
Definitions of types and some structures.
stateObservation::kine::internal::KinematicsInternal::KinematicsInternal
KinematicsInternal()
Definition: rigid-body-kinematics.hpp:507
stateObservation::kine::vectorComponent
Vector3 vectorComponent(const Quaternion &q)
vector part of the quaternion
stateObservation::kine::Orientation::getQuaternionRefUnsafe
CheckedQuaternion & getQuaternionRefUnsafe()
get a reference to the quaternion representation of the orientation without calling the check functio...
stateObservation::kine::internal::KinematicsInternal
Definition: rigid-body-kinematics.hpp:504
stateObservation::AngleAxis
Eigen::AngleAxis< double > AngleAxis
Euler Axis/Angle representation of orientation.
Definition: definitions.hpp:133
stateObservation::kine::rotationMatrixToRotationVector
Vector3 rotationMatrixToRotationVector(const Matrix3 &R)
Transforms the rotation matrix into rotation vector.
stateObservation::kine::integrateKinematics
void integrateKinematics(Vector3 &position, const Vector3 &velocity, double dt)
stateObservation::CheckedItem< Matrix3, false, false, true, true, CheckNaN >
stateObservation::kine::Orientation::getMatrixRefUnsafe
CheckedMatrix3 & getMatrixRefUnsafe()
no checks are performed for these functions, use with caution
stateObservation::kine::Orientation
Definition: rigid-body-kinematics.hpp:354
stateObservation::kine::quaternion
@ quaternion
Definition: rigid-body-kinematics.hpp:314
stateObservation::kine::internal::KinematicsInternal::Flags::orientation
static const Byte orientation
Definition: rigid-body-kinematics.hpp:527
stateObservation::kine::rotationMatrixToRollPitchYaw
Vector3 rotationMatrixToRollPitchYaw(const Matrix3 &R, Vector3 &v)
stateObservation::cst::epsilon1
constexpr double epsilon1
number considered zero when compared to 1
Definition: definitions.hpp:672
stateObservation::kine::Orientation::reset
void reset()
resets the Orientation object.
stateObservation::kine::Orientation::isQuaternionSet
bool isQuaternionSet() const
checks that the quaternion representation of the orientation has been assigned a value.
miscellaneous-algorithms.hpp
Gathers many kinds of algorithms.
stateObservation::kine::Orientation::isMatrixSet
bool isMatrixSet() const
checks that the matrix representation of the orientation has been assigned a value.
stateObservation::kine::LocalKinematics::setToDiffNoAliasLinPart
LocalKinematics & setToDiffNoAliasLinPart(const LocalKinematics &multiplier1, const LocalKinematics &multiplier2)
Linear part of the setToDiffNoAlias(const LocalKinematics &, const LocalKinematics &) function.
stateObservation::kine::Kinematics::operator=
Kinematics & operator=(const LocalKinematics &locK)
fills the Kinematics object given its equivalent in the local frame.
stateObservation::Vector3
Eigen::Vector3d Vector3
3D vector
Definition: definitions.hpp:85
stateObservation::kine::zeroRotationQuaternion
Quaternion zeroRotationQuaternion()
Get the Identity Quaternion.
stateObservation::kine::mergeTiltWithYaw
Matrix3 mergeTiltWithYaw(const Vector3 &Rtez, const Matrix3 &R2, const Vector3 &v=Vector3::UnitX()) noexcept(false)
Merge the roll and pitch from the tilt (R^T e_z) with the yaw from a rotation matrix (minimizes the d...
stateObservation::kine::internal::KinematicsInternal::angVel
CheckedVector3 angVel
Definition: rigid-body-kinematics.hpp:543
stateObservation::Quaternion
Eigen::Quaterniond Quaternion
Quaternion.
Definition: definitions.hpp:127
stateObservation::kine::Orientation::randomRotation
static Orientation randomRotation()
Returns a uniformly distributed random rotation.
stateObservation::kine::orthogonalizeRotationMatrix
Matrix3 orthogonalizeRotationMatrix(const Matrix3 &M)
Projects the Matrix to so(3)
stateObservation::kine::internal::KinematicsInternal::orientation
Orientation orientation
Definition: rigid-body-kinematics.hpp:540
stateObservation::kine::derivatePoseThetaUFD
Vector6 derivatePoseThetaUFD(const Vector6 &v1, const Vector6 &v2, double dt)
stateObservation::kine::internal::KinematicsInternal::angAcc
CheckedVector3 angAcc
Definition: rigid-body-kinematics.hpp:546
stateObservation::kine::Orientation::setMatrix
void setMatrix(bool b=true)
stateObservation::kine::vector6ToHomogeneousMatrix
Matrix4 vector6ToHomogeneousMatrix(const Vector6 &v)
transforms a 6d vector (position theta mu) into a homogeneous matrix
stateObservation::kine::Kinematics::setToDiffNoAliasLinPart
Kinematics & setToDiffNoAliasLinPart(const Kinematics &multiplier1, const Kinematics &multiplier2)
Linear part of the setToDiffNoAlias(const Kinematics &, const Kinematics &) function.
stateObservation
Definition: bidim-elastic-inv-pendulum-dyn-sys.hpp:20
stateObservation::kine::Kinematics::getInverse
Kinematics getInverse() const
returns the inverse of the current kinematics.
stateObservation::kine::Orientation::toAngleAxis
AngleAxis toAngleAxis() const
operator<<
std::ostream & operator<<(std::ostream &os, const stateObservation::kine::Kinematics &k)
stateObservation::kine::LocalKinematics::setToProductNoAlias
LocalKinematics & setToProductNoAlias(const LocalKinematics &operand1, const LocalKinematics &operand2)
computes the composition of two LocalKinematics object.
stateObservation::Vector4
Eigen::Vector4d Vector4
4D vector
Definition: definitions.hpp:91
stateObservation::kine::LocalKinematics::operator=
LocalKinematics & operator=(const Kinematics &kine)
fills the LocalKinematics object given its equivalent in the global frame.
stateObservation::kine::internal::KinematicsInternal::Flags::Byte
unsigned char Byte
Definition: rigid-body-kinematics.hpp:524
stateObservation::kine::Orientation::differentiate
Vector3 differentiate(Orientation R_k1) const
gives the log (rotation vector) of the "left-side" difference of orientation: log of R_k1*(*this)....
stateObservation::kine::internal::KinematicsInternal::linVel
CheckedVector3 linVel
Definition: rigid-body-kinematics.hpp:542
stateObservation::kine::Orientation::fromVector4
Orientation & fromVector4(const Vector4 &v)
stateObservation::kine::matrix
@ matrix
Definition: rigid-body-kinematics.hpp:312
stateObservation::kine::Kinematics::integrate
const Kinematics & integrate(double dt)
integrates the current kinematics over the timestep dt.
stateObservation::kine::quaternionToRotationVector
Vector3 quaternionToRotationVector(const Quaternion &q)
Tranbsform a quaternion into rotation vector.
stateObservation::kine::internal::KinematicsInternal::Flags::angVel
static const Byte angVel
Definition: rigid-body-kinematics.hpp:529
stateObservation::kine::homogeneousMatrixToVector6
Vector6 homogeneousMatrixToVector6(const Matrix4 &M)
transforms a homogeneous matrix into 6d vector (position theta mu)
stateObservation::kine::Kinematics::update
const Kinematics & update(const Kinematics &newValue, double dt, Flags::Byte=Flags::all)
updates the current kinematics (k) with the new ones (k+1).
stateObservation::kine::Orientation::quaternionToMatrix_
const Matrix3 & quaternionToMatrix_() const
stateObservation::kine::rollPitchYawToQuaternion
Quaternion rollPitchYawToQuaternion(double roll, double pitch, double yaw)
stateObservation::kine::LocalKinematics::tempVec_
Vector3 tempVec_
Definition: rigid-body-kinematics.hpp:768
stateObservation::kine::Orientation::setZeroRotation
Orientation & setZeroRotation()
stateObservation::kine::Orientation::zeroRotation
static Orientation zeroRotation()
retruns a zero rotation
stateObservation::kine::internal::KinematicsInternal::Flags::angAcc
static const Byte angAcc
Definition: rigid-body-kinematics.hpp:531
stateObservation::kine::LocalKinematics::setToDiffNoAlias
LocalKinematics & setToDiffNoAlias(const LocalKinematics &multiplier1, const LocalKinematics &multiplier2)
stateObservation::kine::LocalKinematics::tempVec_2
Vector3 tempVec_2
Definition: rigid-body-kinematics.hpp:769
stateObservation::kine::Orientation::setQuaternion
void setQuaternion(bool b=true)
stateObservation::kine::scalarComponent
double scalarComponent(const Quaternion &q)
scalar component of a quaternion
stateObservation::kine::Kinematics::tempVec_
Vector3 tempVec_
Definition: rigid-body-kinematics.hpp:669
stateObservation::kine::derivateRtvMultiplicative
Matrix3 derivateRtvMultiplicative(const Matrix3 &R, const Vector3 &v)