27 #include <gtsam/dllexport.h> 69 SO3
SO3::Expmap(
const Vector3& omega, ChartJacobian H);
92 SO3 SO3::ChartAtOrigin::Retract(
const Vector3& omega, ChartJacobian H);
96 Vector3 SO3::ChartAtOrigin::Local(
const SO3& R, ChartJacobian H);
100 Vector9
SO3::vec(OptionalJacobian<9, 3> H)
const;
102 #ifdef GTSAM_ENABLE_BOOST_SERIALIZATION 103 template <
class Archive>
105 void serialize(Archive& ar, SO3& R,
const unsigned int ) {
106 Matrix3& M = R.matrix_;
107 ar& boost::serialization::make_nvp(
"R11", M(0, 0));
108 ar& boost::serialization::make_nvp(
"R12", M(0, 1));
109 ar& boost::serialization::make_nvp(
"R13", M(0, 2));
110 ar& boost::serialization::make_nvp(
"R21", M(1, 0));
111 ar& boost::serialization::make_nvp(
"R22", M(1, 1));
112 ar& boost::serialization::make_nvp(
"R23", M(1, 2));
113 ar& boost::serialization::make_nvp(
"R31", M(2, 0));
114 ar& boost::serialization::make_nvp(
"R32", M(2, 1));
115 ar& boost::serialization::make_nvp(
"R33", M(2, 2));
125 GTSAM_EXPORT Matrix3 compose(
const Matrix3& M,
const SO3& R,
126 OptionalJacobian<9, 9> H = {});
129 GTSAM_EXPORT Matrix99
Dcompose(
const SO3& R);
141 double theta, sin_theta, one_minus_cos;
143 void init(
bool nearZeroApprox =
false);
147 explicit ExpmapFunctor(
const Vector3& omega,
bool nearZeroApprox =
false);
150 ExpmapFunctor(
const Vector3& axis,
double angle,
bool nearZeroApprox =
false);
164 GTSAM_EXPORT
explicit DexpFunctor(
const Vector3& omega,
bool nearZeroApprox =
false);
172 const Matrix3& dexp()
const {
return dexp_; }
179 GTSAM_EXPORT Vector3 applyInvDexp(
const Vector3& v,
static MatrixNN Hat(const TangentVector &xi)
Definition: SOn-inl.h:29
static SO ChordalMean(const std::vector< SO > &rotations)
static SO AxisAngle(const Vector3 &axis, double theta)
Constructor from axis and angle. Only defined for SO3.
static MatrixDD ExpmapDerivative(const TangentVector &omega)
Derivative of Expmap, currently only defined for SO3.
Definition: SOn-inl.h:72
std::string serialize(const T &input)
serializes to a string
Definition: serialization.h:113
static SO Expmap(const TangentVector &omega, ChartJacobian H={})
Definition: SOn-inl.h:67
static MatrixDD LogmapDerivative(const TangentVector &omega)
Derivative of Logmap, currently only defined for SO3.
Definition: SOn-inl.h:82
Functor implementing Exponential map.
Definition: SO3.h:136
GTSAM_EXPORT Matrix99 Dcompose(const SO3 &R)
(constant) Jacobian of compose wrpt M
typedef and functions to augment Eigen's MatrixXd
Base class and basic functions for Lie types.
Definition: chartTesting.h:28
Definition: OptionalJacobian.h:38
static TangentVector Logmap(const SO &R, ChartJacobian H={})
Definition: SOn-inl.h:77
MatrixDD AdjointMap() const
Adjoint map.
Definition: SOn-inl.h:60
Both LieGroupTraits and Testable.
Definition: Lie.h:229
Functor that implements Exponential map and its derivatives.
Definition: SO3.h:157
static SO ClosestTo(const MatrixNN &M)
static TangentVector Vee(const MatrixNN &X)
Inverse of Hat. See note about xi element order in Hat.
Definition: SOn-inl.h:35
N*N matrix representation of SO(N). N can be Eigen::Dynamic.
VectorN2 vec(OptionalJacobian< internal::NSquaredSO(N), dimension > H={}) const
Definition: SOn-inl.h:88