24#include <gtsam/dllexport.h>
38 return (N < 0) ? Eigen::Dynamic : N * (N - 1) / 2;
42constexpr int NSquaredSO(
int N) {
return (N < 0) ? Eigen::Dynamic : N * N; }
50class SO :
public LieGroup<SO<N>, internal::DimensionSO(N)> {
52 enum { dimension = internal::DimensionSO(N) };
53 using MatrixNN = Eigen::Matrix<double, N, N>;
54 using VectorN2 = Eigen::Matrix<double, internal::NSquaredSO(N), 1>;
55 using MatrixDD = Eigen::Matrix<double, dimension, dimension>;
65 using IsDynamic =
typename std::enable_if<N_ == Eigen::Dynamic, void>::type;
67 using IsFixed =
typename std::enable_if<N_ >= 2,
void>::type;
69 using IsSO3 =
typename std::enable_if<N_ == 3, void>::type;
76 template <
int N_ = N,
typename = IsFixed<N_>>
80 template <
int N_ = N,
typename = IsDynamic<N_>>
81 explicit SO(
size_t n = 0) {
84 matrix_ = Eigen::MatrixXd::Identity(n, n);
88 template <
typename Derived>
89 explicit SO(
const Eigen::MatrixBase<Derived>& R) :
matrix_(R.eval()) {}
92 template <
typename Derived>
98 template <
typename Derived,
int N_ = N,
typename = IsDynamic<N_>>
99 static SO Lift(
size_t n,
const Eigen::MatrixBase<Derived> &R) {
100 Matrix Q = Matrix::Identity(n, n);
101 const int p = R.rows();
102 assert(p >= 0 && p <=
static_cast<int>(n) && R.cols() == p);
103 Q.topLeftCorner(p, p) = R;
108 template <
int M,
int N_ = N,
typename = IsDynamic<N_>>
112 template <
int N_ = N,
typename = IsSO3<N_>>
113 explicit SO(
const Eigen::AngleAxisd& angleAxis) :
matrix_(angleAxis) {}
127 template <
int N_ = N,
typename = IsDynamic<N_>>
128 static SO Random(std::mt19937& rng,
size_t n = 0) {
129 if (n == 0)
throw std::runtime_error(
"SO: Dimensionality not known.");
131 static std::uniform_real_distribution<double> randomAngle(-M_PI, M_PI);
132 const size_t d = SO::Dimension(n);
134 for (
size_t j = 0; j < d; j++) {
135 xi(j) = randomAngle(rng);
141 template <
int N_ = N,
typename = IsFixed<N_>>
154 size_t rows()
const {
return matrix_.rows(); }
155 size_t cols()
const {
return matrix_.cols(); }
161 void print(
const std::string& s = std::string())
const;
163 bool equals(
const SO& other,
double tol)
const {
173 assert(dim() == other.dim());
178 template <
int N_ = N,
typename = IsFixed<N_>>
184 template <
int N_ = N,
typename = IsDynamic<N_>>
196 using TangentVector = Eigen::Matrix<double, dimension, 1>;
200 static int Dim() {
return dimension; }
204 static size_t Dimension(
size_t n) {
return n * (n - 1) / 2; }
207 static size_t AmbientDim(
size_t d) {
return (1 + std::sqrt(1 + 8 * d)) / 2; }
211 size_t dim()
const {
return Dimension(
static_cast<size_t>(
matrix_.rows())); }
228 static MatrixNN
Hat(
const TangentVector& xi);
231 static void Hat(
const Vector &xi, Eigen::Ref<MatrixNN> X);
234 static TangentVector
Vee(
const MatrixNN& X);
251 template <
int N_ = N,
typename = IsDynamic<N_>>
252 static MatrixDD IdentityJacobian(
size_t n) {
253 const size_t d = Dimension(n);
254 return MatrixDD::Identity(d, d);
267 static SO Expmap(
const TangentVector& omega, ChartJacobian H = boost::none);
275 static TangentVector
Logmap(
const SO& R, ChartJacobian H = boost::none);
296 template <
int N_ = N,
typename = IsFixed<N_>>
298 constexpr size_t N2 =
static_cast<size_t>(N * N);
299 Eigen::Matrix<double, N2, dimension> G;
300 for (
size_t j = 0; j < dimension; j++) {
301 const auto X =
Hat(Vector::Unit(dimension, j));
302 G.col(j) = Eigen::Map<const VectorN2>(X.data());
308 template <
int N_ = N,
typename = IsDynamic<N_>>
310 const size_t n2 = n * n, dim = Dimension(n);
312 for (
size_t j = 0; j < dim; j++) {
313 const auto X =
Hat(Vector::Unit(dim, j));
314 G.col(j) = Eigen::Map<const Matrix>(X.data(), n2, 1);
323 template <
class Archive>
324 friend void save(Archive&,
SO&,
const unsigned int);
325 template <
class Archive>
326 friend void load(Archive&,
SO&,
const unsigned int);
327 template <
class Archive>
328 friend void serialize(Archive&,
SO&,
const unsigned int);
329 friend class boost::serialization::access;
335using SOn = SO<Eigen::Dynamic>;
356using DynamicJacobian = OptionalJacobian<Eigen::Dynamic, Eigen::Dynamic>;
359SOn LieGroup<SOn, Eigen::Dynamic>::compose(
const SOn& g, DynamicJacobian H1,
360 DynamicJacobian H2)
const;
363SOn LieGroup<SOn, Eigen::Dynamic>::between(
const SOn& g, DynamicJacobian H1,
364 DynamicJacobian H2)
const;
369template <>
typename SOn::VectorN2
SOn::vec(DynamicJacobian H)
const;
372template<
class Archive>
375 const unsigned int file_version
377 Matrix& M = Q.matrix_;
378 ar& BOOST_SERIALIZATION_NVP(M);
#define GTSAM_MAKE_ALIGNED_OPERATOR_NEW_IF(NeedsToAlign)
This marks a GTSAM object to require alignment.
Definition: types.h:286
make_shared trampoline function to ensure proper alignment
Base class and basic functions for Manifold types.
Base class and basic functions for Lie types.
constexpr int DimensionSO(int N)
Calculate dimensionality of SO<N> manifold, or return Dynamic if so.
Definition: SOn.h:37
Template implementations for SO(n)
Global functions in a separate testing namespace.
Definition: chartTesting.h:28
std::string serialize(const T &input)
serializes to a string
Definition: serialization.h:112
bool equal_with_abs_tol(const Eigen::DenseBase< MATRIX > &A, const Eigen::DenseBase< MATRIX > &B, double tol=1e-9)
equals with a tolerance
Definition: Matrix.h:84
A manifold defines a space in which there is a notion of a linear tangent space that can be centered ...
Definition: concepts.h:30
A CRTP helper class that implements Lie group methods Prerequisites: methods operator*,...
Definition: Lie.h:37
static SO< N > Retract(const TangentVector &v)
Retract at origin: possible in Lie group because it has an identity.
Definition: Lie.h:111
Both LieGroupTraits and Testable.
Definition: Lie.h:229
OptionalJacobian is an Eigen::Ref like class that can take be constructed using either a fixed size o...
Definition: OptionalJacobian.h:39
Manifold of special orthogonal rotation matrices SO<N>.
Definition: SOn.h:50
static SO FromMatrix(const Eigen::MatrixBase< Derived > &R)
Named constructor from Eigen Matrix.
Definition: SOn.h:93
static SO Expmap(const TangentVector &omega, ChartJacobian H=boost::none)
Exponential map at identity - create a rotation from canonical coordinates.
Definition: SOn-inl.h:67
static Matrix VectorizedGenerators()
Calculate N^2 x dim matrix of vectorized Lie algebra generators for SO(N)
Definition: SOn.h:297
SO inverse() const
inverse of a rotation = transpose
Definition: SOn.h:190
VectorN2 vec(OptionalJacobian< internal::NSquaredSO(N), dimension > H=boost::none) const
Return vectorized rotation matrix in column order.
Definition: SOn-inl.h:88
static SO ChordalMean(const std::vector< SO > &rotations)
Named constructor that finds chordal mean = argmin_R \sum sqr(|R-R_i|_F), currently only defined for ...
SO operator*(const SO &other) const
Multiplication.
Definition: SOn.h:172
static TangentVector Vee(const MatrixNN &X)
Inverse of Hat. See note about xi element order in Hat.
Definition: SOn-inl.h:35
MatrixNN matrix_
Rotation matrix.
Definition: SOn.h:60
static TangentVector Logmap(const SO &R, ChartJacobian H=boost::none)
Log map at identity - returns the canonical coordinates of this rotation.
Definition: SOn-inl.h:77
static SO AxisAngle(const Vector3 &axis, double theta)
Constructor from axis and angle. Only defined for SO3.
MatrixDD AdjointMap() const
Adjoint map.
Definition: SO4.cpp:159
static void Hat(const Vector &xi, Eigen::Ref< MatrixNN > X)
In-place version of Hat (see details there), implements recursion.
static int Dim()
Return compile-time dimensionality: fixed size N or Eigen::Dynamic.
Definition: SOn.h:200
static MatrixNN Hat(const TangentVector &xi)
Hat operator creates Lie algebra element corresponding to d-vector, where d is the dimensionality of ...
Definition: SOn-inl.h:29
static MatrixDD ExpmapDerivative(const TangentVector &omega)
Derivative of Expmap, currently only defined for SO3.
Definition: SOn-inl.h:72
static MatrixDD LogmapDerivative(const TangentVector &omega)
Derivative of Logmap, currently only defined for SO3.
Definition: SOn-inl.h:82
SO(const SO< M > &R)
Construct dynamic SO(n) from Fixed SO<M>
Definition: SOn.h:109
SO(size_t n=0)
Construct SO<N> identity for N == Eigen::Dynamic.
Definition: SOn.h:81
SO()
Construct SO<N> identity for N >= 2.
Definition: SOn.h:77
static SO Lift(size_t n, const Eigen::MatrixBase< Derived > &R)
Named constructor from lower dimensional matrix.
Definition: SOn.h:99
static SO identity(size_t n=0)
SO<N> identity for N == Eigen::Dynamic.
Definition: SOn.h:185
static SO Random(std::mt19937 &rng, size_t n=0)
Random SO(n) element (no big claims about uniformity). SO(3) is specialized in SO3....
Definition: SOn.h:128
const MatrixNN & matrix() const
Return matrix.
Definition: SOn.h:152
static SO identity()
SO<N> identity for N >= 2.
Definition: SOn.h:179
static SO Random(std::mt19937 &rng)
Random SO(N) element (no big claims about uniformity)
Definition: SOn.h:142
static SO ClosestTo(const MatrixNN &M)
Named constructor that finds SO(n) matrix closest to M in Frobenius norm, currently only defined for ...
SO(const Eigen::AngleAxisd &angleAxis)
Constructor from AngleAxisd.
Definition: SOn.h:113
static Matrix VectorizedGenerators(size_t n=0)
Calculate n^2 x dim matrix of vectorized Lie algebra generators for SO(n)
Definition: SOn.h:309
SO(const Eigen::MatrixBase< Derived > &R)
Constructor from Eigen Matrix, dynamic version.
Definition: SOn.h:89
static TangentVector Local(const SO &R, ChartJacobian H=boost::none)
Inverse of Retract.
Definition: SOn-inl.h:50
static SO Retract(const TangentVector &xi, ChartJacobian H=boost::none)
Retract uses Cayley map.
Definition: SOn-inl.h:40