24 #include <gtsam/dllexport.h> 27 #ifdef GTSAM_ENABLE_BOOST_SERIALIZATION 28 #include <boost/serialization/nvp.hpp> 33 #include <type_traits> 42 return (N < 0) ? Eigen::Dynamic : N * (N - 1) / 2;
46 constexpr
int NSquaredSO(
int N) {
return (N < 0) ? Eigen::Dynamic : N * N; }
54 class SO :
public LieGroup<SO<N>, internal::DimensionSO(N)> {
56 enum { dimension = internal::DimensionSO(N) };
57 using MatrixNN = Eigen::Matrix<double, N, N>;
58 using VectorN2 = Eigen::Matrix<double, internal::NSquaredSO(N), 1>;
59 using MatrixDD = Eigen::Matrix<double, dimension, dimension>;
69 using IsDynamic =
typename std::enable_if<N_ == Eigen::Dynamic, void>::type;
71 using IsFixed =
typename std::enable_if<N_ >= 2,
void>::type;
73 using IsSO3 =
typename std::enable_if<N_ == 3, void>::type;
80 template <
int N_ = N,
typename = IsFixed<N_>>
81 SO() : matrix_(MatrixNN::Identity()) {}
84 template <
int N_ = N,
typename = IsDynamic<N_>>
85 explicit SO(
size_t n = 0) {
88 matrix_ = Eigen::MatrixXd::Identity(n, n);
92 template <
typename Derived>
93 explicit SO(
const Eigen::MatrixBase<Derived>& R) : matrix_(R.eval()) {}
96 template <
typename Derived>
102 template <
typename Derived,
int N_ = N,
typename = IsDynamic<N_>>
103 static SO Lift(
size_t n,
const Eigen::MatrixBase<Derived> &R) {
104 Matrix Q = Matrix::Identity(n, n);
105 const int p = R.rows();
106 assert(p >= 0 && p <= static_cast<int>(n) && R.cols() == p);
107 Q.topLeftCorner(p, p) = R;
112 template <
int M,
int N_ = N,
typename = IsDynamic<N_>>
113 explicit SO(
const SO<M>& R) : matrix_(R.matrix()) {}
116 template <
int N_ = N,
typename = IsSO3<N_>>
117 explicit SO(
const Eigen::AngleAxisd& angleAxis) : matrix_(angleAxis) {}
120 static SO AxisAngle(
const Vector3& axis,
double theta);
124 static SO ClosestTo(
const MatrixNN& M);
129 static SO ChordalMean(
const std::vector<SO>& rotations);
132 template <
int N_ = N,
typename = IsDynamic<N_>>
133 static SO Random(std::mt19937& rng,
size_t n = 0) {
134 if (n == 0)
throw std::runtime_error(
"SO: Dimensionality not known.");
136 static std::uniform_real_distribution<double> randomAngle(-M_PI, M_PI);
137 const size_t d = SO::Dimension(n);
139 for (
size_t j = 0; j < d; j++) {
140 xi(j) = randomAngle(rng);
146 template <
int N_ = N,
typename = IsFixed<N_>>
157 const MatrixNN&
matrix()
const {
return matrix_; }
159 size_t rows()
const {
return matrix_.rows(); }
160 size_t cols()
const {
return matrix_.cols(); }
166 void print(
const std::string& s = std::string())
const;
168 bool equals(
const SO& other,
double tol)
const {
178 assert(dim() == other.dim());
183 template <
int N_ = N,
typename = IsFixed<N_>>
189 template <
int N_ = N,
typename = IsDynamic<N_>>
201 using TangentVector = Eigen::Matrix<double, dimension, 1>;
205 static int Dim() {
return dimension; }
209 static size_t Dimension(
size_t n) {
return n * (n - 1) / 2; }
212 static size_t AmbientDim(
size_t d) {
return (1 + std::sqrt(1 + 8 * d)) / 2; }
216 size_t dim()
const {
return Dimension(static_cast<size_t>(matrix_.rows())); }
233 static MatrixNN Hat(
const TangentVector& xi);
236 static void Hat(
const Vector &xi, Eigen::Ref<MatrixNN> X);
239 static TangentVector Vee(
const MatrixNN& X);
256 template <
int N_ = N,
typename = IsDynamic<N_>>
257 static MatrixDD IdentityJacobian(
size_t n) {
258 const size_t d = Dimension(n);
259 return MatrixDD::Identity(d, d);
267 MatrixDD AdjointMap()
const;
275 static MatrixDD ExpmapDerivative(
const TangentVector& omega);
283 static MatrixDD LogmapDerivative(
const TangentVector& omega);
301 template <
int N_ = N,
typename = IsFixed<N_>>
303 constexpr
size_t N2 =
static_cast<size_t>(N * N);
304 Eigen::Matrix<double, N2, dimension> G;
305 for (
size_t j = 0; j < dimension; j++) {
306 const auto X = Hat(Vector::Unit(dimension, j));
307 G.col(j) = Eigen::Map<const VectorN2>(X.data());
313 template <
int N_ = N,
typename = IsDynamic<N_>>
315 const size_t n2 = n * n, dim = Dimension(n);
317 for (
size_t j = 0; j < dim; j++) {
318 const auto X = Hat(Vector::Unit(dim, j));
319 G.col(j) = Eigen::Map<const Matrix>(X.data(), n2, 1);
328 #ifdef GTSAM_ENABLE_BOOST_SERIALIZATION 329 template <
class Archive>
330 friend void save(Archive&,
SO&,
const unsigned int);
331 template <
class Archive>
332 friend void load(Archive&,
SO&,
const unsigned int);
333 template <
class Archive>
334 friend void serialize(Archive&,
SO&,
const unsigned int);
335 friend class boost::serialization::access;
382 #ifdef GTSAM_ENABLE_BOOST_SERIALIZATION 384 template<
class Archive>
387 const unsigned int file_version
390 ar& BOOST_SERIALIZATION_NVP(M);
static MatrixNN Hat(const TangentVector &xi)
Definition: SOn-inl.h:29
Definition: OptionalJacobian.h:189
static int Dim()
Return compile-time dimensionality: fixed size N or Eigen::Dynamic.
Definition: SOn.h:205
SO inverse() const
inverse of a rotation = transpose
Definition: SOn.h:195
make_shared trampoline function to ensure proper alignment
std::string serialize(const T &input)
serializes to a string
Definition: serialization.h:113
Template implementations for SO(n)
static SO Identity()
SO<N> identity for N >= 2.
Definition: SOn.h:184
static Matrix VectorizedGenerators()
Calculate N^2 x dim matrix of vectorized Lie algebra generators for SO(N)
Definition: SOn.h:302
SO(const SO< M > &R)
Construct dynamic SO(n) from Fixed SO<M>
Definition: SOn.h:113
Rot3 is a 3D rotation represented as a rotation matrix if the preprocessor symbol GTSAM_USE_QUATERNIO...
Definition: Rot3.h:58
static Matrix VectorizedGenerators(size_t n=0)
Calculate n^2 x dim matrix of vectorized Lie algebra generators for SO(n)
Definition: SOn.h:314
#define GTSAM_MAKE_ALIGNED_OPERATOR_NEW_IF(NeedsToAlign)
Definition: types.h:293
MatrixNN matrix_
Rotation matrix.
Definition: SOn.h:64
Definition: Testable.h:112
Base class and basic functions for Manifold types.
const MatrixNN & matrix() const
Return matrix.
Definition: SOn.h:157
GTSAM_EXPORT void print(const Matrix &A, const std::string &s, std::ostream &stream)
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.cpp.
Definition: SOn.h:133
GTSAM_EXPORT void save(const Matrix &A, const std::string &s, const std::string &filename)
static SO Identity(size_t n=0)
SO<N> identity for N == Eigen::Dynamic.
Definition: SOn.h:190
SO(const Eigen::MatrixBase< Derived > &R)
Constructor from Eigen Matrix, dynamic version.
Definition: SOn.h:93
SO(const Eigen::AngleAxisd &angleAxis)
Constructor from AngleAxisd.
Definition: SOn.h:117
Base class and basic functions for Lie types.
SO()
Construct SO<N> identity for N >= 2.
Definition: SOn.h:81
bool equal_with_abs_tol(const Eigen::DenseBase< MATRIX > &A, const Eigen::DenseBase< MATRIX > &B, double tol=1e-9)
Definition: Matrix.h:80
static SO FromMatrix(const Eigen::MatrixBase< Derived > &R)
Named constructor from Eigen Matrix.
Definition: SOn.h:97
Definition: chartTesting.h:28
static SO Lift(size_t n, const Eigen::MatrixBase< Derived > &R)
Named constructor from lower dimensional matrix.
Definition: SOn.h:103
SO operator*(const SO &other) const
Multiplication.
Definition: SOn.h:177
Definition: OptionalJacobian.h:38
Both LieGroupTraits and Testable.
Definition: Lie.h:229
constexpr int DimensionSO(int N)
Calculate dimensionality of SO<N> manifold, or return Dynamic if so.
Definition: SOn.h:41
static SO< N > Retract(const TangentVector &v)
Retract at origin: possible in Lie group because it has an identity.
Definition: Lie.h:111
static SO Random(std::mt19937 &rng)
Random SO(N) element (no big claims about uniformity)
Definition: SOn.h:147
SO(size_t n=0)
Construct SO<N> identity for N == Eigen::Dynamic.
Definition: SOn.h:85
static TangentVector Vee(const MatrixNN &X)
Inverse of Hat. See note about xi element order in Hat.
Definition: SOn-inl.h:35
VectorN2 vec(OptionalJacobian< internal::NSquaredSO(N), dimension > H={}) const
Definition: SOn-inl.h:88