SO3.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 
21 #pragma once
22 
23 #include <gtsam/geometry/SOn.h>
24 
25 #include <gtsam/base/Lie.h>
26 #include <gtsam/base/Matrix.h>
27 #include <gtsam/dllexport.h>
28 
29 #include <vector>
30 
31 namespace gtsam {
32 
33 using SO3 = SO<3>;
34 
35 // Below are all declarations of SO<3> specializations.
36 // They are *defined* in SO3.cpp.
37 
38 template <>
39 GTSAM_EXPORT
40 SO3 SO3::AxisAngle(const Vector3& axis, double theta);
41 
42 template <>
43 GTSAM_EXPORT
44 SO3 SO3::ClosestTo(const Matrix3& M);
45 
46 template <>
47 GTSAM_EXPORT
48 SO3 SO3::ChordalMean(const std::vector<SO3>& rotations);
49 
50 template <>
51 GTSAM_EXPORT
52 Matrix3 SO3::Hat(const Vector3& xi);
53 
54 template <>
55 GTSAM_EXPORT
56 Vector3 SO3::Vee(const Matrix3& X);
57 
59 template <>
60 Matrix3 SO3::AdjointMap() const;
61 
66 template <>
67 GTSAM_EXPORT
68 SO3 SO3::Expmap(const Vector3& omega, ChartJacobian H);
69 
71 template <>
72 GTSAM_EXPORT
73 Matrix3 SO3::ExpmapDerivative(const Vector3& omega);
74 
79 template <>
80 GTSAM_EXPORT
81 Vector3 SO3::Logmap(const SO3& R, ChartJacobian H);
82 
84 template <>
85 GTSAM_EXPORT
86 Matrix3 SO3::LogmapDerivative(const Vector3& omega);
87 
88 // Chart at origin for SO3 is *not* Cayley but actual Expmap/Logmap
89 template <>
90 GTSAM_EXPORT
91 SO3 SO3::ChartAtOrigin::Retract(const Vector3& omega, ChartJacobian H);
92 
93 template <>
94 GTSAM_EXPORT
95 Vector3 SO3::ChartAtOrigin::Local(const SO3& R, ChartJacobian H);
96 
97 template <>
98 GTSAM_EXPORT
99 Vector9 SO3::vec(OptionalJacobian<9, 3> H) const;
100 
101 #if GTSAM_ENABLE_BOOST_SERIALIZATION
102 template <class Archive>
104 void serialize(Archive& ar, SO3& R, const unsigned int /*version*/) {
105  Matrix3& M = R.matrix_;
106  ar& boost::serialization::make_nvp("R11", M(0, 0));
107  ar& boost::serialization::make_nvp("R12", M(0, 1));
108  ar& boost::serialization::make_nvp("R13", M(0, 2));
109  ar& boost::serialization::make_nvp("R21", M(1, 0));
110  ar& boost::serialization::make_nvp("R22", M(1, 1));
111  ar& boost::serialization::make_nvp("R23", M(1, 2));
112  ar& boost::serialization::make_nvp("R31", M(2, 0));
113  ar& boost::serialization::make_nvp("R32", M(2, 1));
114  ar& boost::serialization::make_nvp("R33", M(2, 2));
115 }
116 #endif
117 
118 namespace so3 {
119 
124 GTSAM_EXPORT Matrix3 compose(const Matrix3& M, const SO3& R,
125  OptionalJacobian<9, 9> H = {});
126 
128 GTSAM_EXPORT Matrix99 Dcompose(const SO3& R);
129 
130 // Below are two functors that allow for saving computation when exponential map
131 // and its derivatives are needed at the same location in so<3>. The second
132 // functor also implements dedicated methods to apply dexp and/or inv(dexp).
133 
137 struct GTSAM_EXPORT ExpmapFunctor {
138  const double theta2, theta;
139  const Matrix3 W, WW;
140  bool nearZero{ false };
141 
142  // Ethan Eade's constants:
143  double A; // A = sin(theta) / theta
144  double B; // B = (1 - cos(theta))
145 
147  explicit ExpmapFunctor(const Vector3& omega);
148 
150  ExpmapFunctor(double nearZeroThresholdSq, const Vector3& axis);
151 
153  ExpmapFunctor(const Vector3& axis, double angle);
154 
156  Matrix3 expmap() const;
157 
158 protected:
159  void init(double nearZeroThresholdSq);
160 };
161 
165 struct GTSAM_EXPORT DexpFunctor : public ExpmapFunctor {
166  const Vector3 omega;
167 
168  // Ethan's C constant used in Jacobians
169  double C; // (1 - A) / theta^2
170 
171  // Constant used in inverse Jacobians
172  double D; // (1 - A/2B) / theta2
173 
174  // Constants used in cross and doubleCross
175  double E; // (2B - A) / theta2
176  double F; // (3C - B) / theta2
177 
179  explicit DexpFunctor(const Vector3& omega);
180 
182  explicit DexpFunctor(const Vector3& omega, double nearZeroThresholdSq, double nearPiThresholdSq);
183 
184  // NOTE(luca): Right Jacobian for Exponential map in SO(3) - equation
185  // (10.86) and following equations in G.S. Chirikjian, "Stochastic Models,
186  // Information Theory, and Lie Groups", Volume 2, 2008.
187  // Expmap(xi + dxi) \approx Expmap(xi) * Expmap(dexp * dxi)
188  // This maps a perturbation dxi=(w,v) in the tangent space to
189  // a perturbation on the manifold Expmap(dexp * xi)
190  Matrix3 rightJacobian() const { return I_3x3 - B * W + C * WW; }
191 
192  // Compute the left Jacobian for Exponential map in SO(3)
193  Matrix3 leftJacobian() const { return I_3x3 + B * W + C * WW; }
194 
197  Matrix3 rightJacobianInverse() const;
198 
199  // Inverse of left Jacobian
201  Matrix3 leftJacobianInverse() const;
202 
204  Vector3 applyRightJacobian(const Vector3& v,
205  OptionalJacobian<3, 3> H1 = {}, OptionalJacobian<3, 3> H2 = {}) const;
206 
208  Vector3 applyRightJacobianInverse(const Vector3& v,
209  OptionalJacobian<3, 3> H1 = {}, OptionalJacobian<3, 3> H2 = {}) const;
210 
212  Vector3 applyLeftJacobian(const Vector3& v,
213  OptionalJacobian<3, 3> H1 = {}, OptionalJacobian<3, 3> H2 = {}) const;
214 
216  Vector3 applyLeftJacobianInverse(const Vector3& v,
217  OptionalJacobian<3, 3> H1 = {}, OptionalJacobian<3, 3> H2 = {}) const;
218 
219 #ifdef GTSAM_ALLOW_DEPRECATED_SINCE_V43
220  inline Matrix3 dexp() const { return rightJacobian(); }
222 
224  inline Matrix3 invDexp() const { return rightJacobianInverse(); }
225 #endif
226 };
227 } // namespace so3
228 
229 /*
230  * Define the traits. internal::MatrixLieGroup provides both Lie group and Testable
231  */
232 
233 template <>
234 struct traits<SO3> : public internal::MatrixLieGroup<SO3> {};
235 
236 template <>
237 struct traits<const SO3> : public internal::MatrixLieGroup<SO3> {};
238 
239 } // end namespace gtsam
SOn.h
N*N matrix representation of SO(N). N can be Eigen::Dynamic.
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::SO< 3 >::ChordalMean
static SO ChordalMean(const std::vector< SO > &rotations)
gtsam::so3::ExpmapFunctor::B
double B
Definition: SO3.h:144
gtsam::SO< 3 >::Hat
static MatrixNN Hat(const TangentVector &xi)
Definition: SOn-inl.h:29
screwPose2::xi
Vector xi
Definition: testPose2.cpp:169
gtsam::so3::DexpFunctor::E
double E
Definition: SO3.h:175
Matrix.h
typedef and functions to augment Eigen's MatrixXd
gtsam::abc_eqf_lib::State
State class representing the state of the Biased Attitude System.
Definition: ABC.h:128
B
Definition: test_numpy_dtypes.cpp:301
gtsam::SO< 3 >::ExpmapDerivative
static MatrixDD ExpmapDerivative(const TangentVector &omega)
Derivative of Expmap, currently only defined for SO3.
Definition: SOn-inl.h:72
X
#define X
Definition: icosphere.cpp:20
gtsam::Vector3
Eigen::Vector3d Vector3
Definition: Vector.h:44
gtsam::SO< 3 >::Expmap
static SO Expmap(const TangentVector &omega, ChartJacobian H={})
Definition: SOn-inl.h:67
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
so3
Definition: testShonanFactor.cpp:38
gtsam::internal::MatrixLieGroup
Both LieGroupTraits and Testable.
Definition: Lie.h:256
gtsam::so3::ExpmapFunctor::A
double A
Definition: SO3.h:143
gtsam::so3::DexpFunctor::D
double D
Definition: SO3.h:172
gtsam::SO< 3 >::AdjointMap
MatrixDD AdjointMap() const
Adjoint map.
Definition: SO4.cpp:158
init
detail::initimpl::constructor< Args... > init()
Binds an existing constructor taking arguments Args...
Definition: pybind11.h:1958
gtsam::SO< 3 >::Logmap
static TangentVector Logmap(const SO &R, ChartJacobian H={})
Definition: SOn-inl.h:77
gtsam::so3::DexpFunctor
Definition: SO3.h:165
gtsam::so3::DexpFunctor::omega
const Vector3 omega
Definition: SO3.h:166
gtsam::so3::ExpmapFunctor::WW
const Matrix3 WW
Definition: SO3.h:139
gtsam::so3::DexpFunctor::leftJacobian
Matrix3 leftJacobian() const
Definition: SO3.h:193
Lie.h
Base class and basic functions for Lie types.
C
Matrix< Scalar, Dynamic, Dynamic > C
Definition: bench_gemm.cpp:50
gtsam
traits
Definition: ABC.h:17
gtsam::so3::Dcompose
GTSAM_EXPORT Matrix99 Dcompose(const SO3 &Q)
(constant) Jacobian of compose wrpt M
Definition: SO3.cpp:59
gtsam::so3::DexpFunctor::C
double C
Definition: SO3.h:169
gtsam::traits
Definition: Group.h:36
gtsam::OptionalJacobian
Definition: OptionalJacobian.h:38
gtsam::so3::DexpFunctor::rightJacobian
Matrix3 rightJacobian() const
Definition: SO3.h:190
gtsam::symbol_shorthand::W
Key W(std::uint64_t j)
Definition: inference/Symbol.h:170
gtsam::so3::DexpFunctor::F
double F
Definition: SO3.h:176
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 >
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
gtsam::SO< 3 >::ClosestTo
static SO ClosestTo(const MatrixNN &M)
M
abc_eqf_lib::State< N > M
Definition: ABC_EQF_Demo.cpp:17
gtsam::SO< 3 >::vec
VectorN2 vec(OptionalJacobian< internal::NSquaredSO(N), dimension > H={}) const
Definition: SOn-inl.h:88
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:68
gtsam::so3::ExpmapFunctor
Definition: SO3.h:137


gtsam
Author(s):
autogenerated on Wed May 28 2025 03:03:22