26 #define QUATERNION_TYPE Eigen::Quaternion<_Scalar,_Options> 31 template<
typename _Scalar,
int _Options>
58 ChartJacobian Hg = boost::none, ChartJacobian Hh = boost::none) {
59 if (Hg) *Hg = h.toRotationMatrix().transpose();
65 ChartJacobian Hg = boost::none, ChartJacobian Hh = boost::none) {
66 Q
d = g.inverse() *
h;
67 if (Hg) *Hg = -d.toRotationMatrix().transpose();
73 ChartJacobian
H = boost::none) {
74 if (
H) *
H = -g.toRotationMatrix();
80 ChartJacobian
H = boost::none) {
84 _Scalar theta2 = omega.dot(omega);
87 _Scalar ha = _Scalar(0.5) *
theta;
89 return Q(
cos(ha), vec.x(), vec.y(), vec.z());
92 Vector3 vec = _Scalar(0.5) * omega;
93 return Q(1.0, vec.x(), vec.y(), vec.z());
98 static TangentVector
Logmap(
const Q&
q, ChartJacobian
H = boost::none) {
103 static const double twoPi = 2.0 *
M_PI, NearlyOne = 1.0 - 1
e-10,
104 NearlyNegativeOne = -1.0 + 1
e-10;
108 const _Scalar qw = q.w();
110 if (qw > NearlyOne) {
113 omega = ( 8. / 3. - 2. / 3. * qw) * q.vec();
114 }
else if (qw < NearlyNegativeOne) {
117 omega = (-8. / 3. - 2. / 3. * qw) * q.vec();
120 _Scalar angle = 2 *
acos(qw),
s =
sqrt(1 - qw * qw);
124 else if (angle < -
M_PI)
126 omega = (angle /
s) * q.vec();
137 static TangentVector
Local(
const Q&
g,
const Q&
h,
138 ChartJacobian H1 = boost::none, ChartJacobian H2 = boost::none) {
141 TangentVector
v = Logmap(b, (H1 || H2) ? &D_v_b : 0);
142 if (H1) *H1 = D_v_b * (*H1);
143 if (H2) *H2 = D_v_b * (*H2);
148 ChartJacobian H1 = boost::none, ChartJacobian H2 = boost::none) {
150 Q
b =
Expmap(v,H2 ? &D_h_v : 0);
151 Q
h = Compose(g, b, H1, H2);
152 if (H2) *H2 = (*H2) * D_h_v;
159 static void Print(
const Q&
q,
const std::string&
str =
"") {
161 std::cout <<
"Eigen::Quaternion: ";
163 std::cout <<
str <<
" ";
164 std::cout << q.vec().transpose() << std::endl;
167 return Between(q1, q2).vec().array().abs().maxCoeff() <
tol;
static TangentVector Local(const Q &g, const Q &h, ChartJacobian H1=boost::none, ChartJacobian H2=boost::none)
static MatrixDD ExpmapDerivative(const TangentVector &omega)
Derivative of Expmap, currently only defined for SO3.
tag to assert a type is a Lie group
OptionalJacobian< 3, 3 > ChartJacobian
QUATERNION_TYPE ManifoldType
static Q Compose(const Q &g, const Q &h, ChartJacobian Hg=boost::none, ChartJacobian Hh=boost::none)
static MatrixDD LogmapDerivative(const TangentVector &omega)
Derivative of Logmap, currently only defined for SO3.
EIGEN_DEVICE_FUNC const SqrtReturnType sqrt() const
Pose2_ Expmap(const Vector3_ &xi)
static Q Between(const Q &g, const Q &h, ChartJacobian Hg=boost::none, ChartJacobian Hh=boost::none)
Eigen::Matrix< _Scalar, 3, 1, _Options, 3, 1 > TangentVector
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
3*3 matrix representation of SO(3)
void g(const string &key, int i)
EIGEN_DEVICE_FUNC const CosReturnType cos() const
static void Print(const Q &q, const std::string &str="")
lie_group_tag structure_category
Group operator syntax flavors.
BetweenFactor< Rot3 > Between
static bool Equals(const Q &q1, const Q &q2, double tol=1e-8)
Array< double, 1, 3 > e(1./3., 0.5, 2.)
EIGEN_DEVICE_FUNC const Scalar & q
Base class and basic functions for Lie types.
A matrix or vector expression mapping an existing expression.
EIGEN_DEVICE_FUNC const AcosReturnType acos() const
multiplicative_group_tag group_flavor
The quaternion class used to represent 3D orientations and rotations.
static Q Inverse(const Q &g, ChartJacobian H=boost::none)
static Q Expmap(const Eigen::Ref< const TangentVector > &omega, ChartJacobian H=boost::none)
Exponential map, using the inlined code from Eigen's conversion from axis/angle.
EIGEN_DEVICE_FUNC const SinReturnType sin() const
The matrix class, also used for vectors and row-vectors.
static Q Retract(const Q &g, const TangentVector &v, ChartJacobian H1=boost::none, ChartJacobian H2=boost::none)
static TangentVector Logmap(const Q &q, ChartJacobian H=boost::none)
We use our own Logmap, as there is a slight bug in Eigen.
Eigen::Quaternion< double, Eigen::DontAlign > Quaternion