SO3.cpp
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 
21 #include <gtsam/base/Matrix.h>
22 #include <gtsam/base/Vector.h>
23 #include <gtsam/base/concepts.h>
24 #include <gtsam/geometry/Point3.h>
25 #include <gtsam/geometry/SO3.h>
26 
27 #include <Eigen/SVD>
28 #include <cmath>
29 #include <limits>
30 
31 namespace gtsam {
32 
33 //******************************************************************************
34 namespace so3 {
35 
36 static constexpr double one_6th = 1.0 / 6.0;
37 static constexpr double one_12th = 1.0 / 12.0;
38 static constexpr double one_24th = 1.0 / 24.0;
39 static constexpr double one_60th = 1.0 / 60.0;
40 static constexpr double one_120th = 1.0 / 120.0;
41 static constexpr double one_180th = 1.0 / 180.0;
42 static constexpr double one_720th = 1.0 / 720.0;
43 static constexpr double one_1260th = 1.0 / 1260.0;
44 
45 GTSAM_EXPORT Matrix99 Dcompose(const SO3& Q) {
46  Matrix99 H;
47  auto R = Q.matrix();
48  H << I_3x3 * R(0, 0), I_3x3 * R(1, 0), I_3x3 * R(2, 0), //
49  I_3x3 * R(0, 1), I_3x3 * R(1, 1), I_3x3 * R(2, 1), //
50  I_3x3 * R(0, 2), I_3x3 * R(1, 2), I_3x3 * R(2, 2);
51  return H;
52 }
53 
54 GTSAM_EXPORT Matrix3 compose(const Matrix3& M, const SO3& R,
56  Matrix3 MR = M * R.matrix();
57  if (H) *H = Dcompose(R);
58  return MR;
59 }
60 
61 void ExpmapFunctor::init(bool nearZeroApprox) {
62  nearZero =
64  if (!nearZero) {
65  const double sin_theta = std::sin(theta);
66  A = sin_theta / theta;
67  const double s2 = std::sin(theta / 2.0);
68  const double one_minus_cos =
69  2.0 * s2 * s2; // numerically better than [1 - cos(theta)]
70  B = one_minus_cos / theta2;
71  } else {
72  // Taylor expansion at 0
73  A = 1.0 - theta2 * one_6th;
74  B = 0.5 - theta2 * one_24th;
75  }
76 }
77 
78 ExpmapFunctor::ExpmapFunctor(const Vector3& omega, bool nearZeroApprox)
79  : theta2(omega.dot(omega)),
80  theta(std::sqrt(theta2)),
82  WW(W * W) {
83  init(nearZeroApprox);
84 }
85 
86 ExpmapFunctor::ExpmapFunctor(const Vector3& axis, double angle,
87  bool nearZeroApprox)
88  : theta2(angle * angle),
89  theta(angle),
90  W(skewSymmetric(axis * angle)),
91  WW(W * W) {
92  init(nearZeroApprox);
93 }
94 
95 SO3 ExpmapFunctor::expmap() const { return SO3(I_3x3 + A * W + B * WW); }
96 
97 DexpFunctor::DexpFunctor(const Vector3& omega, bool nearZeroApprox)
98  : ExpmapFunctor(omega, nearZeroApprox), omega(omega) {
99  if (!nearZero) {
100  C = (1 - A) / theta2;
101  D = (1.0 - A / (2.0 * B)) / theta2;
102  E = (2.0 * B - A) / theta2;
103  F = (3.0 * C - B) / theta2;
104  } else {
105  // Taylor expansion at 0
106  // TODO(Frank): flipping signs here does not trigger any tests: harden!
107  C = one_6th - theta2 * one_120th;
108  D = one_12th + theta2 * one_720th;
109  E = one_12th - theta2 * one_180th;
110  F = one_60th - theta2 * one_1260th;
111  }
112 }
113 
115  // Wv = omega x v
116  const Vector3 Wv = gtsam::cross(omega, v);
117  if (H) {
118  // Apply product rule to (B Wv)
119  // - E * omega.transpose() is 1x3 Jacobian of B with respect to omega
120  // - skewSymmetric(v) is 3x3 Jacobian of Wv = gtsam::cross(omega, v)
121  *H = - Wv * E * omega.transpose() - B * skewSymmetric(v);
122  }
123  return B * Wv;
124 }
125 
127  OptionalJacobian<3, 3> H) const {
128  // WWv = omega x (omega x * v)
129  Matrix3 doubleCrossJacobian;
130  const Vector3 WWv =
131  gtsam::doubleCross(omega, v, H ? &doubleCrossJacobian : nullptr);
132  if (H) {
133  // Apply product rule to (C WWv)
134  // - F * omega.transpose() is 1x3 Jacobian of C with respect to omega
135  // doubleCrossJacobian is 3x3 Jacobian of WWv = gtsam::doubleCross(omega, v)
136  *H = - WWv * F * omega.transpose() + C * doubleCrossJacobian;
137  }
138  return C * WWv;
139 }
140 
141 // Multiplies v with left Jacobian through vector operations only.
143  OptionalJacobian<3, 3> H2) const {
144  Matrix3 D_BWv_w, D_CWWv_w;
145  const Vector3 BWv = crossB(v, H1 ? &D_BWv_w : nullptr);
146  const Vector3 CWWv = doubleCrossC(v, H1 ? &D_CWWv_w : nullptr);
147  if (H1) *H1 = -D_BWv_w + D_CWWv_w;
148  if (H2) *H2 = rightJacobian();
149  return v - BWv + CWWv;
150 }
151 
153  OptionalJacobian<3, 3> H2) const {
154  const Matrix3 invJr = rightJacobianInverse();
155  const Vector3 c = invJr * v;
156  if (H1) {
157  Matrix3 H;
158  applyDexp(c, H); // get derivative H of forward mapping
159  *H1 = -invJr * H;
160  }
161  if (H2) *H2 = invJr;
162  return c;
163 }
164 
167  OptionalJacobian<3, 3> H2) const {
168  Matrix3 D_BWv_w, D_CWWv_w;
169  const Vector3 BWv = crossB(v, H1 ? &D_BWv_w : nullptr);
170  const Vector3 CWWv = doubleCrossC(v, H1 ? &D_CWWv_w : nullptr);
171  if (H1) *H1 = D_BWv_w + D_CWWv_w;
172  if (H2) *H2 = leftJacobian();
173  return v + BWv + CWWv;
174 }
175 
178  OptionalJacobian<3, 3> H2) const {
179  const Matrix3 invJl = leftJacobianInverse();
180  const Vector3 c = invJl * v;
181  if (H1) {
182  Matrix3 H;
183  applyLeftJacobian(c, H); // get derivative H of forward mapping
184  *H1 = -invJl * H;
185  }
186  if (H2) *H2 = invJl;
187  return c;
188 }
189 
190 } // namespace so3
191 
192 //******************************************************************************
193 template <>
194 GTSAM_EXPORT
195 SO3 SO3::AxisAngle(const Vector3& axis, double theta) {
196  return so3::ExpmapFunctor(axis, theta).expmap();
197 }
198 
199 //******************************************************************************
200 template <>
201 GTSAM_EXPORT
202 SO3 SO3::ClosestTo(const Matrix3& M) {
204  const auto& U = svd.matrixU();
205  const auto& V = svd.matrixV();
206  const double det = (U * V.transpose()).determinant();
207  return SO3(U * Vector3(1, 1, det).asDiagonal() * V.transpose());
208 }
209 
210 //******************************************************************************
211 template <>
212 GTSAM_EXPORT
213 SO3 SO3::ChordalMean(const std::vector<SO3>& rotations) {
214  // See Hartley13ijcv:
215  // Cost function C(R) = \sum sqr(|R-R_i|_F)
216  // Closed form solution = ClosestTo(C_e), where C_e = \sum R_i !!!!
217  Matrix3 C_e{Z_3x3};
218  for (const auto& R_i : rotations) {
219  C_e += R_i.matrix();
220  }
221  return ClosestTo(C_e);
222 }
223 
224 //******************************************************************************
225 template <>
226 GTSAM_EXPORT
227 Matrix3 SO3::Hat(const Vector3& xi) {
228  return skewSymmetric(xi);
229 }
230 
231 //******************************************************************************
232 template <>
233 GTSAM_EXPORT
234 Vector3 SO3::Vee(const Matrix3& X) {
235  Vector3 xi;
236  xi(0) = -X(1, 2);
237  xi(1) = +X(0, 2);
238  xi(2) = -X(0, 1);
239  return xi;
240 }
241 
242 //******************************************************************************
243 template <>
244 GTSAM_EXPORT
245 Matrix3 SO3::AdjointMap() const {
246  return matrix_;
247 }
248 
249 //******************************************************************************
250 template <>
251 GTSAM_EXPORT
252 SO3 SO3::Expmap(const Vector3& omega, ChartJacobian H) {
253  if (H) {
254  so3::DexpFunctor impl(omega);
255  *H = impl.dexp();
256  return impl.expmap();
257  } else {
258  return so3::ExpmapFunctor(omega).expmap();
259  }
260 }
261 
262 template <>
263 GTSAM_EXPORT
264 Matrix3 SO3::ExpmapDerivative(const Vector3& omega) {
265  return so3::DexpFunctor(omega).dexp();
266 }
267 
268 //******************************************************************************
269 /* Right Jacobian for Log map in SO(3) - equation (10.86) and following
270  equations in G.S. Chirikjian, "Stochastic Models, Information Theory, and Lie
271  Groups", Volume 2, 2008.
272 
273  logmap( Rhat * expmap(omega) ) \approx logmap(Rhat) + Jrinv * omega
274 
275  where Jrinv = LogmapDerivative(omega). This maps a perturbation on the
276  manifold (expmap(omega)) to a perturbation in the tangent space (Jrinv *
277  omega)
278  */
279 template <>
280 GTSAM_EXPORT
281 Matrix3 SO3::LogmapDerivative(const Vector3& omega) {
282  using std::cos;
283  using std::sin;
284 
285  double theta2 = omega.dot(omega);
286  if (theta2 <= std::numeric_limits<double>::epsilon()) return I_3x3;
287  double theta = std::sqrt(theta2); // rotation angle
288 
289  // element of Lie algebra so(3): W = omega^
290  const Matrix3 W = Hat(omega);
291  return I_3x3 + 0.5 * W +
292  (1 / (theta * theta) - (1 + cos(theta)) / (2 * theta * sin(theta))) *
293  W * W;
294 }
295 
296 //******************************************************************************
297 template <>
298 GTSAM_EXPORT
299 Vector3 SO3::Logmap(const SO3& Q, ChartJacobian H) {
300  using std::sin;
301  using std::sqrt;
302 
303  // note switch to base 1
304  const Matrix3& R = Q.matrix();
305  const double &R11 = R(0, 0), R12 = R(0, 1), R13 = R(0, 2);
306  const double &R21 = R(1, 0), R22 = R(1, 1), R23 = R(1, 2);
307  const double &R31 = R(2, 0), R32 = R(2, 1), R33 = R(2, 2);
308 
309  // Get trace(R)
310  const double tr = R.trace();
311 
312  Vector3 omega;
313 
314  // when trace == -1, i.e., when theta = +-pi, +-3pi, +-5pi, etc.
315  // we do something special
316  if (tr + 1.0 < 1e-3) {
317  if (R33 > R22 && R33 > R11) {
318  // R33 is the largest diagonal, a=3, b=1, c=2
319  const double W = R21 - R12;
320  const double Q1 = 2.0 + 2.0 * R33;
321  const double Q2 = R31 + R13;
322  const double Q3 = R23 + R32;
323  const double r = sqrt(Q1);
324  const double one_over_r = 1 / r;
325  const double norm = sqrt(Q1*Q1 + Q2*Q2 + Q3*Q3 + W*W);
326  const double sgn_w = W < 0 ? -1.0 : 1.0;
327  const double mag = M_PI - (2 * sgn_w * W) / norm;
328  const double scale = 0.5 * one_over_r * mag;
329  omega = sgn_w * scale * Vector3(Q2, Q3, Q1);
330  } else if (R22 > R11) {
331  // R22 is the largest diagonal, a=2, b=3, c=1
332  const double W = R13 - R31;
333  const double Q1 = 2.0 + 2.0 * R22;
334  const double Q2 = R23 + R32;
335  const double Q3 = R12 + R21;
336  const double r = sqrt(Q1);
337  const double one_over_r = 1 / r;
338  const double norm = sqrt(Q1*Q1 + Q2*Q2 + Q3*Q3 + W*W);
339  const double sgn_w = W < 0 ? -1.0 : 1.0;
340  const double mag = M_PI - (2 * sgn_w * W) / norm;
341  const double scale = 0.5 * one_over_r * mag;
342  omega = sgn_w * scale * Vector3(Q3, Q1, Q2);
343  } else {
344  // R11 is the largest diagonal, a=1, b=2, c=3
345  const double W = R32 - R23;
346  const double Q1 = 2.0 + 2.0 * R11;
347  const double Q2 = R12 + R21;
348  const double Q3 = R31 + R13;
349  const double r = sqrt(Q1);
350  const double one_over_r = 1 / r;
351  const double norm = sqrt(Q1*Q1 + Q2*Q2 + Q3*Q3 + W*W);
352  const double sgn_w = W < 0 ? -1.0 : 1.0;
353  const double mag = M_PI - (2 * sgn_w * W) / norm;
354  const double scale = 0.5 * one_over_r * mag;
355  omega = sgn_w * scale * Vector3(Q1, Q2, Q3);
356  }
357  } else {
358  double magnitude;
359  const double tr_3 = tr - 3.0; // could be non-negative if the matrix is off orthogonal
360  if (tr_3 < -1e-6) {
361  // this is the normal case -1 < trace < 3
362  double theta = acos((tr - 1.0) / 2.0);
363  magnitude = theta / (2.0 * sin(theta));
364  } else {
365  // when theta near 0, +-2pi, +-4pi, etc. (trace near 3.0)
366  // use Taylor expansion: theta \approx 1/2-(t-3)/12 + O((t-3)^2)
367  // see https://github.com/borglab/gtsam/issues/746 for details
368  magnitude = 0.5 - tr_3 / 12.0 + tr_3*tr_3/60.0;
369  }
370  omega = magnitude * Vector3(R32 - R23, R13 - R31, R21 - R12);
371  }
372 
373  if (H) *H = LogmapDerivative(omega);
374  return omega;
375 }
376 
377 //******************************************************************************
378 // Chart at origin for SO3 is *not* Cayley but actual Expmap/Logmap
379 
380 template <>
381 GTSAM_EXPORT
382 SO3 SO3::ChartAtOrigin::Retract(const Vector3& omega, ChartJacobian H) {
383  return Expmap(omega, H);
384 }
385 
386 template <>
387 GTSAM_EXPORT
388 Vector3 SO3::ChartAtOrigin::Local(const SO3& R, ChartJacobian H) {
389  return Logmap(R, H);
390 }
391 
392 //******************************************************************************
393 // local vectorize
394 static Vector9 vec3(const Matrix3& R) {
395  return Eigen::Map<const Vector9>(R.data());
396 }
397 
398 // so<3> generators
399 static std::vector<Matrix3> G3({SO3::Hat(Vector3::Unit(0)),
400  SO3::Hat(Vector3::Unit(1)),
401  SO3::Hat(Vector3::Unit(2))});
402 
403 // vectorized generators
404 static const Matrix93 P3 =
405  (Matrix93() << vec3(G3[0]), vec3(G3[1]), vec3(G3[2])).finished();
406 
407 //******************************************************************************
408 template <>
409 GTSAM_EXPORT
410 Vector9 SO3::vec(OptionalJacobian<9, 3> H) const {
411  const Matrix3& R = matrix_;
412  if (H) {
413  // As Luca calculated (for SO4), this is (I3 \oplus R) * P3
414  *H << R * P3.block<3, 3>(0, 0), R * P3.block<3, 3>(3, 0),
415  R * P3.block<3, 3>(6, 0);
416  }
417  return gtsam::vec3(R);
418 }
419 //******************************************************************************
420 
421 } // end namespace gtsam
gtsam::SO3
SO< 3 > SO3
Definition: SO3.h:33
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::so3::DexpFunctor::applyLeftJacobian
Vector3 applyLeftJacobian(const Vector3 &v, OptionalJacobian< 3, 3 > H1={}, OptionalJacobian< 3, 3 > H2={}) const
Multiplies with leftJacobian(), with optional derivatives.
Definition: SO3.cpp:165
gtsam::so3::one_180th
static constexpr double one_180th
Definition: SO3.cpp:41
Eigen::ComputeFullV
@ ComputeFullV
Definition: Constants.h:397
Vector.h
typedef and functions to augment Eigen's VectorXd
e
Array< double, 1, 3 > e(1./3., 0.5, 2.)
gtsam::so3::ExpmapFunctor::B
double B
Definition: SO3.h:144
screwPose2::xi
Vector xi
Definition: testPose2.cpp:148
ceres::sin
Jet< T, N > sin(const Jet< T, N > &f)
Definition: jet.h:439
gtsam::so3::DexpFunctor::E
double E
Definition: SO3.h:172
gtsam::so3::DexpFunctor::applyDexp
Vector3 applyDexp(const Vector3 &v, OptionalJacobian< 3, 3 > H1={}, OptionalJacobian< 3, 3 > H2={}) const
Multiplies with dexp(), with optional derivatives.
Definition: SO3.cpp:142
c
Scalar Scalar * c
Definition: benchVecAdd.cpp:17
Matrix.h
typedef and functions to augment Eigen's MatrixXd
gtsam::so3::DexpFunctor::rightJacobianInverse
Matrix3 rightJacobianInverse() const
Inverse of right Jacobian.
Definition: SO3.h:193
B
Definition: test_numpy_dtypes.cpp:299
gtsam::so3::one_120th
static constexpr double one_120th
Definition: SO3.cpp:40
Eigen::ComputeFullU
@ ComputeFullU
Definition: Constants.h:393
gtsam::so3::ExpmapFunctor::ExpmapFunctor
ExpmapFunctor(const Vector3 &omega, bool nearZeroApprox=false)
Constructor with element of Lie algebra so(3)
Definition: SO3.cpp:78
gtsam::vec3
static Vector9 vec3(const Matrix3 &R)
Definition: SO3.cpp:394
gtsam::so3::one_24th
static constexpr double one_24th
Definition: SO3.cpp:38
X
#define X
Definition: icosphere.cpp:20
concepts.h
gtsam::so3::ExpmapFunctor::theta
const double theta
Definition: SO3.h:138
Point3.h
3D Point
gtsam::Vector3
Eigen::Vector3d Vector3
Definition: Vector.h:44
gtsam::so3::one_60th
static constexpr double one_60th
Definition: SO3.cpp:39
gtsam::skewSymmetric
Matrix3 skewSymmetric(double wx, double wy, double wz)
Definition: base/Matrix.h:400
P3
static double P3[]
Definition: jv.c:563
svd
cout<< "Here is the matrix m:"<< endl<< m<< endl;JacobiSVD< MatrixXf > svd(m, ComputeThinU|ComputeThinV)
ceres::acos
Jet< T, N > acos(const Jet< T, N > &f)
Definition: jet.h:432
determinant
void determinant(const MatrixType &m)
Definition: determinant.cpp:14
ceres::cos
Jet< T, N > cos(const Jet< T, N > &f)
Definition: jet.h:426
biased_x_rotation::omega
const double omega
Definition: testPreintegratedRotation.cpp:32
so3
Definition: testShonanFactor.cpp:38
SO3.h
3*3 matrix representation of SO(3)
gtsam::so3::one_720th
static constexpr double one_720th
Definition: SO3.cpp:42
epsilon
static double epsilon
Definition: testRot3.cpp:37
Expmap
Pose2_ Expmap(const Vector3_ &xi)
Definition: InverseKinematicsExampleExpressions.cpp:47
A
Definition: test_numpy_dtypes.cpp:298
gtsam::so3::DexpFunctor::crossB
Vector3 crossB(const Vector3 &v, OptionalJacobian< 3, 3 > H={}) const
Computes B * (omega x v).
Definition: SO3.cpp:114
scale
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 scale
Definition: gnuplot_common_settings.hh:54
gtsam::cross
Point3 cross(const Point3 &p, const Point3 &q, OptionalJacobian< 3, 3 > H1, OptionalJacobian< 3, 3 > H2)
cross product
Definition: Point3.cpp:64
gtsam::SO::matrix
const MatrixNN & matrix() const
Return matrix.
Definition: SOn.h:158
gtsam::so3::DexpFunctor::doubleCrossC
Vector3 doubleCrossC(const Vector3 &v, OptionalJacobian< 3, 3 > H={}) const
Computes C * (omega x (omega x v)).
Definition: SO3.cpp:126
gtsam::so3::ExpmapFunctor::A
double A
Definition: SO3.h:143
gtsam::so3::DexpFunctor::D
double D
Definition: SO3.h:169
gtsam::dot
double dot(const V1 &a, const V2 &b)
Definition: Vector.h:196
gtsam::G3
static std::vector< Matrix3 > G3({SO3::Hat(Vector3::Unit(0)), SO3::Hat(Vector3::Unit(1)), SO3::Hat(Vector3::Unit(2))})
gtsam::so3::one_6th
static constexpr double one_6th
Definition: SO3.cpp:36
gtsam::so3::DexpFunctor::applyInvDexp
Vector3 applyInvDexp(const Vector3 &v, OptionalJacobian< 3, 3 > H1={}, OptionalJacobian< 3, 3 > H2={}) const
Multiplies with dexp().inverse(), with optional derivatives.
Definition: SO3.cpp:152
Eigen::Map
A matrix or vector expression mapping an existing array of data.
Definition: Map.h:94
gtsam::so3::DexpFunctor::applyLeftJacobianInverse
Vector3 applyLeftJacobianInverse(const Vector3 &v, OptionalJacobian< 3, 3 > H1={}, OptionalJacobian< 3, 3 > H2={}) const
Multiplies with leftJacobianInverse(), with optional derivatives.
Definition: SO3.cpp:176
gtsam::so3::DexpFunctor::omega
const Vector3 omega
Definition: SO3.h:163
Q2
static double Q2[8]
Definition: ndtri.c:122
Eigen::JacobiSVD
Two-sided Jacobi SVD decomposition of a rectangular matrix.
Definition: ForwardDeclarations.h:278
gtsam::so3::ExpmapFunctor::expmap
SO3 expmap() const
Rodrigues formula.
Definition: SO3.cpp:95
Eigen::Quaternion
The quaternion class used to represent 3D orientations and rotations.
Definition: ForwardDeclarations.h:293
gtsam::so3::ExpmapFunctor::WW
const Matrix3 WW
Definition: SO3.h:139
gtsam::so3::DexpFunctor::leftJacobian
Matrix3 leftJacobian() const
Definition: SO3.h:187
gtsam
traits
Definition: SFMdata.h:40
gtsam::so3::Dcompose
GTSAM_EXPORT Matrix99 Dcompose(const SO3 &Q)
(constant) Jacobian of compose wrpt M
Definition: SO3.cpp:45
gtsam::so3::DexpFunctor::C
double C
Definition: SO3.h:166
gtsam::OptionalJacobian
Definition: OptionalJacobian.h:38
gtsam::so3::DexpFunctor::rightJacobian
Matrix3 rightJacobian() const
Definition: SO3.h:184
gtsam::symbol_shorthand::W
Key W(std::uint64_t j)
Definition: inference/Symbol.h:170
gtsam::so3::DexpFunctor::F
double F
Definition: SO3.h:173
std
Definition: BFloat16.h:88
Q1
static double Q1[8]
Definition: ndtri.c:94
v
Array< int, Dynamic, 1 > v
Definition: Array_initializer_list_vector_cxx11.cpp:1
gtsam::so3::ExpmapFunctor::theta2
const double theta2
Definition: SO3.h:138
gtsam::SO< 3 >
U
@ U
Definition: testDecisionTree.cpp:342
V
MatrixXcd V
Definition: EigenSolver_EigenSolver_MatrixType.cpp:15
Eigen::Matrix< double, 9, 3 >
gtsam::so3::DexpFunctor::DexpFunctor
DexpFunctor(const Vector3 &omega, bool nearZeroApprox=false)
Constructor with element of Lie algebra so(3)
Definition: SO3.cpp:97
gtsam::so3::ExpmapFunctor::init
void init(bool nearZeroApprox=false)
Definition: SO3.cpp:61
M_PI
#define M_PI
Definition: mconf.h:117
gtsam::so3::DexpFunctor::leftJacobianInverse
Matrix3 leftJacobianInverse() const
Definition: SO3.h:196
gtsam::so3::ExpmapFunctor::nearZero
bool nearZero
Definition: SO3.h:140
so3::R12
SO3 R12
Definition: testShonanFactor.cpp:44
ceres::sqrt
Jet< T, N > sqrt(const Jet< T, N > &f)
Definition: jet.h:418
gtsam::so3::one_12th
static constexpr double one_12th
Definition: SO3.cpp:37
gtsam::so3::one_1260th
static constexpr double one_1260th
Definition: SO3.cpp:43
Matrix93
Eigen::Matrix< double, 9, 3 > Matrix93
Definition: testExpressionFactor.cpp:138
R
Rot2 R(Rot2::fromAngle(0.1))
gtsam::so3::compose
GTSAM_EXPORT Matrix3 compose(const Matrix3 &M, const SO3 &R, OptionalJacobian< 9, 9 > H)
Definition: SO3.cpp:54
gtsam::so3::ExpmapFunctor
Definition: SO3.h:137
gtsam::doubleCross
Point3 doubleCross(const Point3 &p, const Point3 &q, OptionalJacobian< 3, 3 > H1, OptionalJacobian< 3, 3 > H2)
double cross product
Definition: Point3.cpp:72
gtsam::so3::ExpmapFunctor::W
const Matrix3 W
Definition: SO3.h:139
M
Matrix< RealScalar, Dynamic, Dynamic > M
Definition: bench_gemm.cpp:51


gtsam
Author(s):
autogenerated on Wed Jan 1 2025 04:03:26