27#include <gtsam/dllexport.h>
69SO3
SO3::Expmap(
const Vector3& omega, ChartJacobian H);
92SO3 SO3::ChartAtOrigin::Retract(
const Vector3& omega, ChartJacobian H);
96Vector3 SO3::ChartAtOrigin::Local(
const SO3& R, ChartJacobian H);
100Vector9
SO3::vec(OptionalJacobian<9, 3> H)
const;
103template <
class Archive>
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));
123GTSAM_EXPORT Matrix3 compose(
const Matrix3& M,
const SO3& R,
124 OptionalJacobian<9, 9> H = boost::none);
127GTSAM_EXPORT Matrix99 Dcompose(
const SO3& R);
139 double theta, sin_theta, one_minus_cos;
141 void init(
bool nearZeroApprox =
false);
145 explicit ExpmapFunctor(
const Vector3& omega,
bool nearZeroApprox =
false);
148 ExpmapFunctor(
const Vector3& axis,
double angle,
bool nearZeroApprox =
false);
162 GTSAM_EXPORT
explicit DexpFunctor(
const Vector3& omega,
bool nearZeroApprox =
false);
170 const Matrix3& dexp()
const {
return dexp_; }
typedef and functions to augment Eigen's MatrixXd
Base class and basic functions for Lie types.
N*N matrix representation of 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
A manifold defines a space in which there is a notion of a linear tangent space that can be centered ...
Definition: concepts.h:30
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
Functor implementing Exponential map.
Definition: SO3.h:134
Functor that implements Exponential map and its derivatives.
Definition: SO3.h:155
GTSAM_EXPORT Vector3 applyDexp(const Vector3 &v, OptionalJacobian< 3, 3 > H1=boost::none, OptionalJacobian< 3, 3 > H2=boost::none) const
Multiplies with dexp(), with optional derivatives.
Definition: SO3.cpp:101
GTSAM_EXPORT DexpFunctor(const Vector3 &omega, bool nearZeroApprox=false)
Constructor with element of Lie algebra so(3)
Definition: SO3.cpp:90
GTSAM_EXPORT Vector3 applyInvDexp(const Vector3 &v, OptionalJacobian< 3, 3 > H1=boost::none, OptionalJacobian< 3, 3 > H2=boost::none) const
Multiplies with dexp().inverse(), with optional derivatives.
Definition: SO3.cpp:120
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
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 ...
static TangentVector Vee(const MatrixNN &X)
Inverse of Hat. See note about xi element order in Hat.
Definition: SOn-inl.h:35
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 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
static SO ClosestTo(const MatrixNN &M)
Named constructor that finds SO(n) matrix closest to M in Frobenius norm, currently only defined for ...