27 #include <gtsam/dllexport.h> 96 Vector3 SO3::ChartAtOrigin::Local(
const SO3&
R, ChartJacobian
H);
102 #ifdef GTSAM_ENABLE_BOOST_SERIALIZATION 103 template <
class Archive>
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,
141 double theta, sin_theta, one_minus_cos;
143 void init(
bool nearZeroApprox =
false);
172 const Matrix3&
dexp()
const {
return dexp_; }
static MatrixNN Hat(const TangentVector &xi)
static SO ChordalMean(const std::vector< SO > &rotations)
Matrix< RealScalar, Dynamic, Dynamic > M
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.
std::string serialize(const T &input)
serializes to a string
static SO Expmap(const TangentVector &omega, ChartJacobian H={})
static MatrixDD LogmapDerivative(const TangentVector &omega)
Derivative of Logmap, currently only defined for SO3.
Rot2 R(Rot2::fromAngle(0.1))
static Cal3_S2 K(500, 500, 0.1, 640/2, 480/2)
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
Functor implementing Exponential map.
MatrixNN matrix_
Rotation matrix.
const Matrix3 & dexp() const
GTSAM_EXPORT Matrix99 Dcompose(const SO3 &Q)
(constant) Jacobian of compose wrpt M
Array< int, Dynamic, 1 > v
Vector::Scalar omega(const Vector &t, const Vector &s, RealScalar angle)
Base class and basic functions for Lie types.
static TangentVector Logmap(const SO &R, ChartJacobian H={})
MatrixDD AdjointMap() const
Adjoint map.
Both LieGroupTraits and Testable.
Functor that implements Exponential map and its derivatives.
detail::initimpl::constructor< Args... > init()
Binds an existing constructor taking arguments Args...
static SO ClosestTo(const MatrixNN &M)
static TangentVector Vee(const MatrixNN &X)
Inverse of Hat. See note about xi element order in Hat.
N*N matrix representation of SO(N). N can be Eigen::Dynamic.
GTSAM_EXPORT Matrix3 compose(const Matrix3 &M, const SO3 &R, OptionalJacobian< 9, 9 > H)
VectorN2 vec(OptionalJacobian< internal::NSquaredSO(N), dimension > H={}) const