Rot3.h
Go to the documentation of this file.
1 /* ----------------------------------------------------------------------------
2 
3  * GTSAM Copyright 2010, Georgia Tech Research Corporation,
4  * Atlanta, Georgia 30332-0415
5  * All Rights Reserved
6  * Authors: Frank Dellaert, et al. (see THANKS for the full author list)
7 
8  * See LICENSE for the license information
9 
10  * -------------------------------------------------------------------------- */
11 
22 // \callgraph
23 
24 #pragma once
25 
26 #include <gtsam/geometry/Unit3.h>
28 #include <gtsam/geometry/SO3.h>
29 #include <gtsam/base/concepts.h>
30 #include <gtsam/config.h> // Get GTSAM_USE_QUATERNIONS macro
31 
32 #include <random>
33 
34 // You can override the default coordinate mode using this flag
35 #ifndef ROT3_DEFAULT_COORDINATES_MODE
36  #ifdef GTSAM_USE_QUATERNIONS
37  // Exponential map is very cheap for quaternions
38  #define ROT3_DEFAULT_COORDINATES_MODE Rot3::EXPMAP
39  #else
40  // If user doesn't require GTSAM_ROT3_EXPMAP in cmake when building
41  #ifndef GTSAM_ROT3_EXPMAP
42  // For rotation matrices, the Cayley transform is a fast retract alternative
43  #define ROT3_DEFAULT_COORDINATES_MODE Rot3::CAYLEY
44  #else
45  #define ROT3_DEFAULT_COORDINATES_MODE Rot3::EXPMAP
46  #endif
47  #endif
48 #endif
49 
50 namespace gtsam {
51 
58 class GTSAM_EXPORT Rot3 : public LieGroup<Rot3, 3> {
59  private:
60 
61 #ifdef GTSAM_USE_QUATERNIONS
62 
63  gtsam::Quaternion quaternion_;
64 #else
66 #endif
67 
68  public:
71 
73  Rot3();
74 
81  Rot3(const Point3& col1, const Point3& col2, const Point3& col3);
82 
84  Rot3(double R11, double R12, double R13,
85  double R21, double R22, double R23,
86  double R31, double R32, double R33);
87 
95  template <typename Derived>
96 #ifdef GTSAM_USE_QUATERNIONS
97  explicit Rot3(const Eigen::MatrixBase<Derived>& R) {
98  quaternion_ = Matrix3(R);
99  }
100 #else
101  explicit Rot3(const Eigen::MatrixBase<Derived>& R) : rot_(R) {
102  }
103 #endif
104 
109 #ifdef GTSAM_USE_QUATERNIONS
110  explicit Rot3(const Matrix3& R) : quaternion_(R) {}
111 #else
112  explicit Rot3(const Matrix3& R) : rot_(R) {}
113 #endif
114 
118 #ifdef GTSAM_USE_QUATERNIONS
119  explicit Rot3(const SO3& R) : quaternion_(R.matrix()) {}
120 #else
121  explicit Rot3(const SO3& R) : rot_(R) {}
122 #endif
123 
128  Rot3(const Quaternion& q);
129  Rot3(double w, double x, double y, double z) : Rot3(Quaternion(w, x, y, z)) {}
130 
137  static Rot3 Random(std::mt19937 & rng);
138 
140  virtual ~Rot3() {}
141 
142  /* Static member function to generate some well known rotations */
143 
145  static Rot3 Rx(double t);
146 
148  static Rot3 Ry(double t);
149 
151  static Rot3 Rz(double t);
152 
154  static Rot3 RzRyRx(double x, double y, double z,
155  OptionalJacobian<3, 1> Hx = {},
156  OptionalJacobian<3, 1> Hy = {},
157  OptionalJacobian<3, 1> Hz = {});
158 
160  inline static Rot3 RzRyRx(const Vector& xyz,
161  OptionalJacobian<3, 3> H = {}) {
162 #ifndef NDEBUG
163  if (xyz.size() != 3) {
164  throw;
165  }
166 #endif
167  Rot3 out;
168  if (H) {
169  Vector3 Hx, Hy, Hz;
170  out = RzRyRx(xyz(0), xyz(1), xyz(2), Hx, Hy, Hz);
171  (*H) << Hx, Hy, Hz;
172  } else
173  out = RzRyRx(xyz(0), xyz(1), xyz(2));
174  return out;
175  }
176 
178  static Rot3 Yaw (double t) { return Rz(t); }
179 
181  static Rot3 Pitch(double t) { return Ry(t); }
182 
184  static Rot3 Roll (double t) { return Rx(t); }
185 
200  static Rot3 Ypr(double y, double p, double r,
201  OptionalJacobian<3, 1> Hy = {},
202  OptionalJacobian<3, 1> Hp = {},
203  OptionalJacobian<3, 1> Hr = {}) {
204  return RzRyRx(r, p, y, Hr, Hp, Hy);
205  }
206 
208  static Rot3 Quaternion(double w, double x, double y, double z) {
209  gtsam::Quaternion q(w, x, y, z);
210  return Rot3(q);
211  }
212 
219  static Rot3 AxisAngle(const Point3& axis, double angle) {
220  // Convert to unit vector.
221  Vector3 unitAxis = Unit3(axis).unitVector();
222 #ifdef GTSAM_USE_QUATERNIONS
223  return gtsam::Quaternion(Eigen::AngleAxis<double>(angle, unitAxis));
224 #else
225  return Rot3(SO3::AxisAngle(unitAxis,angle));
226 #endif
227  }
228 
235  static Rot3 AxisAngle(const Unit3& axis, double angle) {
236  return AxisAngle(axis.unitVector(),angle);
237  }
238 
244  static Rot3 Rodrigues(const Vector3& w) {
245  return Rot3::Expmap(w);
246  }
247 
255  static Rot3 Rodrigues(double wx, double wy, double wz) {
256  return Rodrigues(Vector3(wx, wy, wz));
257  }
258 
260  static Rot3 AlignPair(const Unit3& axis, const Unit3& a_p, const Unit3& b_p);
261 
263  static Rot3 AlignTwoPairs(const Unit3& a_p, const Unit3& b_p, //
264  const Unit3& a_q, const Unit3& b_q);
265 
275  static Rot3 ClosestTo(const Matrix3& M) { return Rot3(SO3::ClosestTo(M)); }
276 
287  Rot3 normalized() const;
288 
292 
294  void print(const std::string& s="") const;
295 
297  bool equals(const Rot3& p, double tol = 1e-9) const;
298 
302 
304  inline static Rot3 Identity() {
305  return Rot3();
306  }
307 
309  Rot3 operator*(const Rot3& R2) const;
310 
312  Rot3 inverse() const {
313 #ifdef GTSAM_USE_QUATERNIONS
314  return Rot3(quaternion_.inverse());
315 #else
316  return Rot3(rot_.matrix().transpose());
317 #endif
318  }
319 
325  Rot3 conjugate(const Rot3& cRb) const {
326  // TODO: do more efficiently by using Eigen or quaternion properties
327  return cRb * (*this) * cRb.inverse();
328  }
329 
333 
345 #ifndef GTSAM_USE_QUATERNIONS
347 #endif
348  };
349 
350 #ifndef GTSAM_USE_QUATERNIONS
351 
352  // Cayley chart around origin
353  struct CayleyChart {
354  static Rot3 Retract(const Vector3& v, OptionalJacobian<3, 3> H = {});
355  static Vector3 Local(const Rot3& r, OptionalJacobian<3, 3> H = {});
356  };
357 
359  Rot3 retractCayley(const Vector& omega) const {
360  return compose(CayleyChart::Retract(omega));
361  }
362 
364  Vector3 localCayley(const Rot3& other) const {
365  return CayleyChart::Local(between(other));
366  }
367 
368 #endif
369 
373 
378  static Rot3 Expmap(const Vector3& v, OptionalJacobian<3,3> H = {}) {
379  if(H) *H = Rot3::ExpmapDerivative(v);
380 #ifdef GTSAM_USE_QUATERNIONS
382 #else
383  return Rot3(traits<SO3>::Expmap(v));
384 #endif
385  }
386 
391  static Vector3 Logmap(const Rot3& R, OptionalJacobian<3,3> H = {});
392 
394  static Matrix3 ExpmapDerivative(const Vector3& x);
395 
397  static Matrix3 LogmapDerivative(const Vector3& x);
398 
400  Matrix3 AdjointMap() const { return matrix(); }
401 
402  // Chart at origin, depends on compile-time flag ROT3_DEFAULT_COORDINATES_MODE
403  struct GTSAM_EXPORT ChartAtOrigin {
404  static Rot3 Retract(const Vector3& v, ChartJacobian H = {});
405  static Vector3 Local(const Rot3& r, ChartJacobian H = {});
406  };
407 
408  using LieGroup<Rot3, 3>::inverse; // version with derivative
409 
413 
417  Point3 rotate(const Point3& p, OptionalJacobian<3,3> H1 = {},
418  OptionalJacobian<3,3> H2 = {}) const;
419 
421  Point3 operator*(const Point3& p) const;
422 
424  Point3 unrotate(const Point3& p, OptionalJacobian<3,3> H1 = {},
425  OptionalJacobian<3,3> H2={}) const;
426 
430 
432  Unit3 rotate(const Unit3& p, OptionalJacobian<2,3> HR = {},
433  OptionalJacobian<2,2> Hp = {}) const;
434 
436  Unit3 unrotate(const Unit3& p, OptionalJacobian<2,3> HR = {},
437  OptionalJacobian<2,2> Hp = {}) const;
438 
440  Unit3 operator*(const Unit3& p) const;
441 
445 
447  Matrix3 matrix() const;
448 
452  Matrix3 transpose() const;
453 
455  Point3 column(int index) const;
456 
457  Point3 r1() const;
458  Point3 r2() const;
459  Point3 r3() const;
460 
465  Vector3 xyz(OptionalJacobian<3, 3> H = {}) const;
466 
471  Vector3 ypr(OptionalJacobian<3, 3> H = {}) const;
472 
477  Vector3 rpy(OptionalJacobian<3, 3> H = {}) const;
478 
485  double roll(OptionalJacobian<1, 3> H = {}) const;
486 
493  double pitch(OptionalJacobian<1, 3> H = {}) const;
494 
501  double yaw(OptionalJacobian<1, 3> H = {}) const;
502 
506 
515  std::pair<Unit3, double> axisAngle() const;
516 
520  gtsam::Quaternion toQuaternion() const;
521 
527  Rot3 slerp(double t, const Rot3& other) const;
528 
530  GTSAM_EXPORT friend std::ostream &operator<<(std::ostream &os, const Rot3& p);
531 
533 
534  private:
535 #ifdef GTSAM_ENABLE_BOOST_SERIALIZATION
536 
537  friend class boost::serialization::access;
538  template <class ARCHIVE>
539  void serialize(ARCHIVE& ar, const unsigned int /*version*/) {
540 #ifndef GTSAM_USE_QUATERNIONS
541  Matrix3& M = rot_.matrix_;
542  ar& boost::serialization::make_nvp("rot11", M(0, 0));
543  ar& boost::serialization::make_nvp("rot12", M(0, 1));
544  ar& boost::serialization::make_nvp("rot13", M(0, 2));
545  ar& boost::serialization::make_nvp("rot21", M(1, 0));
546  ar& boost::serialization::make_nvp("rot22", M(1, 1));
547  ar& boost::serialization::make_nvp("rot23", M(1, 2));
548  ar& boost::serialization::make_nvp("rot31", M(2, 0));
549  ar& boost::serialization::make_nvp("rot32", M(2, 1));
550  ar& boost::serialization::make_nvp("rot33", M(2, 2));
551 #else
552  ar& boost::serialization::make_nvp("w", quaternion_.w());
553  ar& boost::serialization::make_nvp("x", quaternion_.x());
554  ar& boost::serialization::make_nvp("y", quaternion_.y());
555  ar& boost::serialization::make_nvp("z", quaternion_.z());
556 #endif
557  }
558 #endif
559 
560 #ifdef GTSAM_USE_QUATERNIONS
561  // only align if quaternion, Matrix3 has no alignment requirements
562  public:
564 #endif
565  };
566 
568  using Rot3Vector = std::vector<Rot3, Eigen::aligned_allocator<Rot3>>;
569 
580  GTSAM_EXPORT std::pair<Matrix3, Vector3> RQ(
581  const Matrix3& A, OptionalJacobian<3, 9> H = {});
582 
583  template<>
584  struct traits<Rot3> : public internal::LieGroup<Rot3> {};
585 
586  template<>
587  struct traits<const Rot3> : public internal::LieGroup<Rot3> {};
588 
589 } // namespace gtsam
590 
w
RowVector3d w
Definition: Matrix_resize_int.cpp:3
H
set noclip points set clip one set noclip two set bar set border lt lw set xdata set ydata set zdata set x2data set y2data set boxwidth set dummy y set format x g set format y g set format x2 g set format y2 g set format z g set angles radians set nogrid set key title set key left top Right noreverse box linetype linewidth samplen spacing width set nolabel set noarrow set nologscale set logscale x set set pointsize set encoding default set nopolar set noparametric set set set set surface set nocontour set clabel set mapping cartesian set nohidden3d set cntrparam order set cntrparam linear set cntrparam levels auto set cntrparam points set size set set xzeroaxis lt lw set x2zeroaxis lt lw set yzeroaxis lt lw set y2zeroaxis lt lw set tics in set ticslevel set tics set mxtics default set mytics default set mx2tics default set my2tics default set xtics border mirror norotate autofreq set ytics border mirror norotate autofreq set ztics border nomirror norotate autofreq set nox2tics set noy2tics set timestamp bottom norotate set rrange[*:*] noreverse nowriteback set trange[*:*] noreverse nowriteback set urange[*:*] noreverse nowriteback set vrange[*:*] noreverse nowriteback set xlabel matrix size set x2label set timefmt d m y n H
Definition: gnuplot_common_settings.hh:74
gtsam::SO< 3 >::AxisAngle
static SO AxisAngle(const Vector3 &axis, double theta)
Constructor from axis and angle. Only defined for SO3.
gtsam::Quaternion
Eigen::Quaternion< double, Eigen::DontAlign > Quaternion
Definition: geometry/Quaternion.h:180
gtsam::Rot3::RzRyRx
static Rot3 RzRyRx(const Vector &xyz, OptionalJacobian< 3, 3 > H={})
Rotations around Z, Y, then X axes as in http://en.wikipedia.org/wiki/Rotation_matrix,...
Definition: Rot3.h:160
rng
static std::mt19937 rng
Definition: timeFactorOverhead.cpp:31
gtsam::column
const MATRIX::ConstColXpr column(const MATRIX &A, size_t j)
Definition: base/Matrix.h:210
gtsam::between
Expression< T > between(const Expression< T > &t1, const Expression< T > &t2)
Definition: nonlinear/expressions.h:17
s
RealScalar s
Definition: level1_cplx_impl.h:126
e
Array< double, 1, 3 > e(1./3., 0.5, 2.)
gtsam::operator<<
std::ostream & operator<<(std::ostream &os, const Dih6 &m)
Definition: testGroup.cpp:109
gtsam::Rot3::Rot3
Rot3(const SO3 &R)
Definition: Rot3.h:121
gtsam::Rot3::Rodrigues
static Rot3 Rodrigues(double wx, double wy, double wz)
Definition: Rot3.h:255
r2
static const double r2
Definition: testSmartRangeFactor.cpp:32
gtsam::Rot3::Quaternion
static Rot3 Quaternion(double w, double x, double y, double z)
Definition: Rot3.h:208
gtsam::Rot3::Identity
static Rot3 Identity()
identity rotation for group operation
Definition: Rot3.h:304
gtsam::Rot3::ClosestTo
static Rot3 ClosestTo(const Matrix3 &M)
Definition: Rot3.h:275
x
set noclip points set clip one set noclip two set bar set border lt lw set xdata set ydata set zdata set x2data set y2data set boxwidth set dummy x
Definition: gnuplot_common_settings.hh:12
Eigen::AngleAxis
Represents a 3D rotation as a rotation angle around an arbitrary 3D axis.
Definition: ForwardDeclarations.h:290
gtsam::Rot3::Yaw
static Rot3 Yaw(double t)
Positive yaw is to right (as in aircraft heading). See ypr.
Definition: Rot3.h:178
concepts.h
gtsam::Vector3
Eigen::Vector3d Vector3
Definition: Vector.h:44
os
ofstream os("timeSchurFactors.csv")
gtsam::Rot3::retractCayley
Rot3 retractCayley(const Vector &omega) const
Retraction from R^3 to Rot3 manifold using the Cayley transform.
Definition: Rot3.h:359
r1
static const double r1
Definition: testSmartRangeFactor.cpp:32
gtsam::Vector
Eigen::VectorXd Vector
Definition: Vector.h:39
gtsam::Rot3::Ypr
static Rot3 Ypr(double y, double p, double r, OptionalJacobian< 3, 1 > Hy={}, OptionalJacobian< 3, 1 > Hp={}, OptionalJacobian< 3, 1 > Hr={})
Definition: Rot3.h:200
gtsam::Rot3::Roll
static Rot3 Roll(double t)
Definition: Rot3.h:184
gtsam::operator*
Point2 operator*(double s, const Point2 &p)
multiply with scalar
Definition: Point2.h:52
Unit3.h
gtsam::SO::matrix_
MatrixNN matrix_
Rotation matrix.
Definition: SOn.h:65
biased_x_rotation::omega
const double omega
Definition: testPreintegratedRotation.cpp:32
gtsam::compose
Expression< T > compose(const Expression< T > &t1, const Expression< T > &t2)
Definition: nonlinear/expressions.h:23
SO3.h
3*3 matrix representation of SO(3)
Expmap
Pose2_ Expmap(const Vector3_ &xi)
Definition: InverseKinematicsExampleExpressions.cpp:47
gtsam::print
void print(const Matrix &A, const string &s, ostream &stream)
Definition: Matrix.cpp:156
A
Definition: test_numpy_dtypes.cpp:298
gtsam::unrotate
Point3_ unrotate(const Rot3_ &x, const Point3_ &p)
Definition: slam/expressions.h:109
gtsam::rotate
Point3_ rotate(const Rot3_ &x, const Point3_ &p)
Definition: slam/expressions.h:97
Eigen::numext::q
EIGEN_DEVICE_FUNC const Scalar & q
Definition: SpecialFunctionsImpl.h:1984
gtsam::SO::matrix
const MatrixNN & matrix() const
Return matrix.
Definition: SOn.h:158
gtsam::internal::LieGroup
Both LieGroupTraits and Testable.
Definition: Lie.h:229
gtsam::Rot3
Rot3 is a 3D rotation represented as a rotation matrix if the preprocessor symbol GTSAM_USE_QUATERNIO...
Definition: Rot3.h:58
gtsam::Rot3::Rodrigues
static Rot3 Rodrigues(const Vector3 &w)
Definition: Rot3.h:244
gtsam::Rot3::conjugate
Rot3 conjugate(const Rot3 &cRb) const
Definition: Rot3.h:325
gtsam::Rot3Vector
std::vector< Rot3, Eigen::aligned_allocator< Rot3 > > Rot3Vector
std::vector of Rot3s, used in Matlab wrapper
Definition: Rot3.h:568
gtsam::Rot3::AdjointMap
Matrix3 AdjointMap() const
Definition: Rot3.h:400
gtsam::Rot3::Pitch
static Rot3 Pitch(double t)
Positive pitch is up (increasing aircraft altitude).See ypr.
Definition: Rot3.h:181
gtsam::Rot3::~Rot3
virtual ~Rot3()
Definition: Rot3.h:140
r3
static const double r3
Definition: testSmartRangeFactor.cpp:32
gtsam::Rot3::ChartAtOrigin
Definition: Rot3.h:403
pybind_wrapper_test_script.z
z
Definition: pybind_wrapper_test_script.py:61
gtsam::Rot3::CayleyChart
Definition: Rot3.h:353
gtsam::Rot3::inverse
Rot3 inverse() const
inverse of a rotation
Definition: Rot3.h:312
out
std::ofstream out("Result.txt")
gtsam::Rot3::AxisAngle
static Rot3 AxisAngle(const Unit3 &axis, double angle)
Definition: Rot3.h:235
gtsam::equals
Definition: Testable.h:112
gtsam::Rot3::EXPMAP
@ EXPMAP
Use the Lie group exponential map to retract.
Definition: Rot3.h:344
y
Scalar * y
Definition: level1_cplx_impl.h:124
matrix
Map< Matrix< T, Dynamic, Dynamic, ColMajor >, 0, OuterStride<> > matrix(T *data, int rows, int cols, int stride)
Definition: gtsam/3rdparty/Eigen/blas/common.h:110
gtsam::Rot3::localCayley
Vector3 localCayley(const Rot3 &other) const
Inverse of retractCayley.
Definition: Rot3.h:364
gtsam::Rot3::Rot3
Rot3(const Matrix3 &R)
Definition: Rot3.h:112
Eigen::Quaternion
The quaternion class used to represent 3D orientations and rotations.
Definition: ForwardDeclarations.h:293
so3::R2
SO3 R2
Definition: testShonanFactor.cpp:43
gtsam
traits
Definition: SFMdata.h:40
gtsam::Rot3::rot_
SO3 rot_
Definition: Rot3.h:65
gtsam::traits
Definition: Group.h:36
gtsam::OptionalJacobian
Definition: OptionalJacobian.h:38
gtsam::Rot3::ExpmapDerivative
static Matrix3 ExpmapDerivative(const Vector3 &x)
Derivative of Expmap.
Definition: Rot3.cpp:237
Quaternion.h
Lie Group wrapper for Eigen Quaternions.
gtsam::Rot3::Expmap
static Rot3 Expmap(const Vector3 &v, OptionalJacobian< 3, 3 > H={})
Definition: Rot3.h:378
p
float * p
Definition: Tutorial_Map_using.cpp:9
gtsam::Rot3::Rot3
Rot3(const Eigen::MatrixBase< Derived > &R)
Definition: Rot3.h:101
v
Array< int, Dynamic, 1 > v
Definition: Array_initializer_list_vector_cxx11.cpp:1
gtsam::LieGroup
Definition: Lie.h:37
gtsam::SO< 3 >
gtsam::tol
const G double tol
Definition: Group.h:79
gtsam::Point3
Vector3 Point3
Definition: Point3.h:38
gtsam::Rot3::CoordinatesMode
CoordinatesMode
Definition: Rot3.h:343
gtsam::SO< 3 >::ClosestTo
static SO ClosestTo(const MatrixNN &M)
Eigen::MatrixBase
Base class for all dense matrices, vectors, and expressions.
Definition: MatrixBase.h:48
gtsam::Unit3
Represents a 3D point on a unit sphere.
Definition: Unit3.h:42
gtsam::Unit3::unitVector
Vector3 unitVector(OptionalJacobian< 3, 2 > H={}) const
Return unit-norm Vector.
Definition: Unit3.cpp:151
align_3::t
Point2 t(10, 10)
cRb
gtsam::Rot3 cRb
Definition: testEssentialMatrixFactor.cpp:33
so3::R12
SO3 R12
Definition: testShonanFactor.cpp:44
gtsam::Rot3::CAYLEY
@ CAYLEY
Retract and localCoordinates using the Cayley transform.
Definition: Rot3.h:346
GTSAM_MAKE_ALIGNED_OPERATOR_NEW
#define GTSAM_MAKE_ALIGNED_OPERATOR_NEW
Definition: types.h:279
pybind_wrapper_test_script.other
other
Definition: pybind_wrapper_test_script.py:42
R
Rot2 R(Rot2::fromAngle(0.1))
gtsam::RQ
pair< Matrix3, Vector3 > RQ(const Matrix3 &A, OptionalJacobian< 3, 9 > H)
Definition: Rot3.cpp:247
gtsam::Rot3::AxisAngle
static Rot3 AxisAngle(const Point3 &axis, double angle)
Definition: Rot3.h:219
gtsam::Rot3::Rot3
Rot3(double w, double x, double y, double z)
Definition: Rot3.h:129
HR
#define HR
Definition: mincover.c:26
M
Matrix< RealScalar, Dynamic, Dynamic > M
Definition: bench_gemm.cpp:51


gtsam
Author(s):
autogenerated on Sun Dec 22 2024 04:13:08