geometry/Quaternion.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 
18 #pragma once
19 
20 #include <gtsam/base/Lie.h>
21 #include <gtsam/base/concepts.h>
22 #include <gtsam/geometry/SO3.h> // Logmap/Expmap derivatives
23 #include <limits>
24 #include <iostream>
25 
26 #define QUATERNION_TYPE Eigen::Quaternion<_Scalar,_Options>
27 
28 namespace gtsam {
29 
30 // Define traits
31 template<typename _Scalar, int _Options>
34  typedef QUATERNION_TYPE Q;
35 
38 
41  static Q Identity() {
42  return Q::Identity();
43  }
44 
48  inline constexpr static auto dimension = 3;
51 
55  static Q Compose(const Q &g, const Q & h,
56  ChartJacobian Hg = {}, ChartJacobian Hh = {}) {
57  if (Hg) *Hg = h.toRotationMatrix().transpose();
58  if (Hh) *Hh = I_3x3;
59  return g * h;
60  }
61 
62  static Q Between(const Q &g, const Q & h,
63  ChartJacobian Hg = {}, ChartJacobian Hh = {}) {
64  Q d = g.inverse() * h;
65  if (Hg) *Hg = -d.toRotationMatrix().transpose();
66  if (Hh) *Hh = I_3x3;
67  return d;
68  }
69 
70  static Q Inverse(const Q &g,
71  ChartJacobian H = {}) {
72  if (H) *H = -g.toRotationMatrix();
73  return g.inverse();
74  }
75 
78  ChartJacobian H = {}) {
79  using std::cos;
80  using std::sin;
81  if (H) *H = SO3::ExpmapDerivative(omega.template cast<double>());
82  _Scalar theta2 = omega.dot(omega);
84  _Scalar theta = std::sqrt(theta2);
85  _Scalar ha = _Scalar(0.5) * theta;
86  Vector3 vec = (sin(ha) / theta) * omega;
87  return Q(cos(ha), vec.x(), vec.y(), vec.z());
88  } else {
89  // first order approximation sin(theta/2)/theta = 0.5
90  Vector3 vec = _Scalar(0.5) * omega;
91  return Q(1.0, vec.x(), vec.y(), vec.z());
92  }
93  }
94 
96  static TangentVector Logmap(const Q& q, ChartJacobian H = {}) {
97  using std::acos;
98  using std::sqrt;
99 
100  // define these compile time constants to avoid std::abs:
101  static const double twoPi = 2.0 * M_PI, NearlyOne = 1.0 - 1e-10,
102  NearlyNegativeOne = -1.0 + 1e-10;
103 
104  TangentVector omega;
105 
106  const _Scalar qw = q.w();
107  // See Quaternion-Logmap.nb in doc for Taylor expansions
108  if (qw > NearlyOne) {
109  // Taylor expansion of (angle / s) at 1
110  // (2 + 2 * (1-qw) / 3) * q.vec();
111  omega = ( 8. / 3. - 2. / 3. * qw) * q.vec();
112  } else if (qw < NearlyNegativeOne) {
113  // Taylor expansion of (angle / s) at -1
114  // (-2 - 2 * (1 + qw) / 3) * q.vec();
115  omega = (-8. / 3. - 2. / 3. * qw) * q.vec();
116  } else {
117  // Normal, away from zero case
118  if (qw > 0) {
119  _Scalar angle = 2 * acos(qw), s = sqrt(1 - qw * qw);
120  // Important: convert to [-pi,pi] to keep error continuous
121  if (angle > M_PI)
122  angle -= twoPi;
123  else if (angle < -M_PI)
124  angle += twoPi;
125  omega = (angle / s) * q.vec();
126  } else {
127  // Make sure that we are using a canonical quaternion with w > 0
128  _Scalar angle = 2 * acos(-qw), s = sqrt(1 - qw * qw);
129  if (angle > M_PI)
130  angle -= twoPi;
131  else if (angle < -M_PI)
132  angle += twoPi;
133  omega = (angle / s) * -q.vec();
134  }
135  }
136 
137  if(H) *H = SO3::LogmapDerivative(omega.template cast<double>());
138  return omega;
139  }
140 
141  using LieAlgebra = Matrix3;
142 
143  static Matrix3 Hat(const Vector3& v) {
144  return SO3::Hat(v);
145  }
146 
147  static Vector3 Vee(const Matrix3& X) {
148  return SO3::Vee(X);
149  }
150 
154 
155  static TangentVector Local(const Q& g, const Q& h,
156  ChartJacobian H1 = {}, ChartJacobian H2 = {}) {
157  Q b = Between(g, h, H1, H2);
158  Matrix3 D_v_b;
159  TangentVector v = Logmap(b, (H1 || H2) ? &D_v_b : 0);
160  if (H1) *H1 = D_v_b * (*H1);
161  if (H2) *H2 = D_v_b * (*H2);
162  return v;
163  }
164 
165  static Q Retract(const Q& g, const TangentVector& v,
166  ChartJacobian H1 = {}, ChartJacobian H2 = {}) {
167  Matrix3 D_h_v;
168  Q b = Expmap(v,H2 ? &D_h_v : 0);
169  Q h = Compose(g, b, H1, H2);
170  if (H2) *H2 = (*H2) * D_h_v;
171  return h;
172  }
173 
177  static void Print(const Q& q, const std::string& str = "") {
178  if (str.size() == 0)
179  std::cout << "Eigen::Quaternion: ";
180  else
181  std::cout << str << " ";
182  std::cout << q.vec().transpose() << std::endl;
183  }
184  static bool Equals(const Q& q1, const Q& q2, double tol = 1e-8) {
185  return Between(q1, q2).vec().array().abs().maxCoeff() < tol;
186  }
188 };
189 
191 
192 } // \namespace gtsam
193 
gtsam::traits< QUATERNION_TYPE >::group_flavor
multiplicative_group_tag group_flavor
Definition: geometry/Quaternion.h:37
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::Quaternion
Eigen::Quaternion< double, Eigen::DontAlign > Quaternion
Definition: geometry/Quaternion.h:190
s
RealScalar s
Definition: level1_cplx_impl.h:126
e
Array< double, 1, 3 > e(1./3., 0.5, 2.)
d
static const double d[K][N]
Definition: igam.h:11
gtsam::SO< 3 >::Hat
static MatrixNN Hat(const TangentVector &xi)
Definition: SOn-inl.h:29
ceres::sin
Jet< T, N > sin(const Jet< T, N > &f)
Definition: jet.h:439
gtsam::SO< 3 >::ExpmapDerivative
static MatrixDD ExpmapDerivative(const TangentVector &omega)
Derivative of Expmap, currently only defined for SO3.
Definition: SOn-inl.h:72
gtsam::traits< QUATERNION_TYPE >::Identity
static Q Identity()
Definition: geometry/Quaternion.h:41
X
#define X
Definition: icosphere.cpp:20
concepts.h
gtsam::Vector3
Eigen::Vector3d Vector3
Definition: Vector.h:44
gtsam::traits< QUATERNION_TYPE >::ManifoldType
QUATERNION_TYPE ManifoldType
Definition: geometry/Quaternion.h:33
h
const double h
Definition: testSimpleHelicopter.cpp:19
Q
Quaternion Q
Definition: testQuaternion.cpp:27
ceres::acos
Jet< T, N > acos(const Jet< T, N > &f)
Definition: jet.h:432
gtsam::traits< QUATERNION_TYPE >::Print
static void Print(const Q &q, const std::string &str="")
Definition: geometry/Quaternion.h:177
ceres::cos
Jet< T, N > cos(const Jet< T, N > &f)
Definition: jet.h:426
gtsam::SO< 3 >::LogmapDerivative
static MatrixDD LogmapDerivative(const TangentVector &omega)
Derivative of Logmap, currently only defined for SO3.
Definition: SOn-inl.h:82
biased_x_rotation::omega
const double omega
Definition: testPreintegratedRotation.cpp:32
gtsam::multiplicative_group_tag
Group operator syntax flavors.
Definition: Group.h:33
SO3.h
3*3 matrix representation of SO(3)
epsilon
static double epsilon
Definition: testRot3.cpp:37
gtsam::traits< QUATERNION_TYPE >::TangentVector
Eigen::Matrix< _Scalar, 3, 1, _Options, 3, 1 > TangentVector
Definition: geometry/Quaternion.h:50
Expmap
Pose2_ Expmap(const Vector3_ &xi)
Definition: InverseKinematicsExampleExpressions.cpp:47
gtsam::traits< QUATERNION_TYPE >::Expmap
static Q Expmap(const Eigen::Ref< const TangentVector > &omega, ChartJacobian H={})
Exponential map, using the inlined code from Eigen's conversion from axis/angle.
Definition: geometry/Quaternion.h:77
gtsam::traits< QUATERNION_TYPE >::LieAlgebra
Matrix3 LieAlgebra
Definition: geometry/Quaternion.h:141
Eigen::numext::q
EIGEN_DEVICE_FUNC const Scalar & q
Definition: SpecialFunctionsImpl.h:1984
gtsam::traits< QUATERNION_TYPE >::Local
static TangentVector Local(const Q &g, const Q &h, ChartJacobian H1={}, ChartJacobian H2={})
Definition: geometry/Quaternion.h:155
gtsam::traits< QUATERNION_TYPE >::Inverse
static Q Inverse(const Q &g, ChartJacobian H={})
Definition: geometry/Quaternion.h:70
gtsam::traits< QUATERNION_TYPE >::Vee
static Vector3 Vee(const Matrix3 &X)
Definition: geometry/Quaternion.h:147
gtsam::traits< QUATERNION_TYPE >::Compose
static Q Compose(const Q &g, const Q &h, ChartJacobian Hg={}, ChartJacobian Hh={})
Definition: geometry/Quaternion.h:55
g
void g(const string &key, int i)
Definition: testBTree.cpp:41
str
Definition: pytypes.h:1560
gtsam::b
const G & b
Definition: Group.h:79
gtsam::traits< QUATERNION_TYPE >::Equals
static bool Equals(const Q &q1, const Q &q2, double tol=1e-8)
Definition: geometry/Quaternion.h:184
Between
BetweenFactor< Rot3 > Between
Definition: testRot3Optimization.cpp:31
Eigen::Quaternion
The quaternion class used to represent 3D orientations and rotations.
Definition: ForwardDeclarations.h:293
Lie.h
Base class and basic functions for Lie types.
Eigen::Ref
A matrix or vector expression mapping an existing expression.
Definition: Ref.h:281
gtsam
traits
Definition: SFMdata.h:40
QUATERNION_TYPE
#define QUATERNION_TYPE
Definition: geometry/Quaternion.h:26
gtsam::traits< QUATERNION_TYPE >::Hat
static Matrix3 Hat(const Vector3 &v)
Definition: geometry/Quaternion.h:143
gtsam::traits
Definition: Group.h:36
gtsam::OptionalJacobian
Definition: OptionalJacobian.h:38
gtsam::lie_group_tag
tag to assert a type is a Lie group
Definition: Lie.h:164
v
Array< int, Dynamic, 1 > v
Definition: Array_initializer_list_vector_cxx11.cpp:1
gtsam::traits< QUATERNION_TYPE >::structure_category
lie_group_tag structure_category
Definition: geometry/Quaternion.h:36
gtsam::tol
const G double tol
Definition: Group.h:79
gtsam::SO< 3 >::Vee
static TangentVector Vee(const MatrixNN &X)
Inverse of Hat. See note about xi element order in Hat.
Definition: SOn-inl.h:35
Eigen::Matrix
The matrix class, also used for vectors and row-vectors.
Definition: 3rdparty/Eigen/Eigen/src/Core/Matrix.h:178
gtsam::traits< QUATERNION_TYPE >::ChartJacobian
OptionalJacobian< 3, 3 > ChartJacobian
Definition: geometry/Quaternion.h:49
gtsam::traits< QUATERNION_TYPE >::Retract
static Q Retract(const Q &g, const TangentVector &v, ChartJacobian H1={}, ChartJacobian H2={})
Definition: geometry/Quaternion.h:165
M_PI
#define M_PI
Definition: mconf.h:117
gtsam::traits< QUATERNION_TYPE >::Between
static Q Between(const Q &g, const Q &h, ChartJacobian Hg={}, ChartJacobian Hh={})
Definition: geometry/Quaternion.h:62
ceres::sqrt
Jet< T, N > sqrt(const Jet< T, N > &f)
Definition: jet.h:418
gtsam::traits< QUATERNION_TYPE >::Q
QUATERNION_TYPE Q
Definition: geometry/Quaternion.h:34
gtsam::traits< QUATERNION_TYPE >::Logmap
static TangentVector Logmap(const Q &q, ChartJacobian H={})
We use our own Logmap, as there is a slight bug in Eigen.
Definition: geometry/Quaternion.h:96


gtsam
Author(s):
autogenerated on Wed Mar 19 2025 03:03:14