26 #define QUATERNION_TYPE Eigen::Quaternion<_Scalar,_Options> 31 template<
typename _Scalar,
int _Options>
58 ChartJacobian Hg = {}, ChartJacobian Hh = {}) {
59 if (Hg) *Hg = h.toRotationMatrix().transpose();
65 ChartJacobian Hg = {}, ChartJacobian Hh = {}) {
66 Q
d = g.inverse() *
h;
67 if (Hg) *Hg = -d.toRotationMatrix().transpose();
73 ChartJacobian
H = {}) {
74 if (
H) *
H = -g.toRotationMatrix();
80 ChartJacobian
H = {}) {
84 _Scalar theta2 = omega.dot(omega);
87 _Scalar ha = _Scalar(0.5) * theta;
89 return Q(
cos(ha), vec.x(), vec.y(), vec.z());
93 return Q(1.0, vec.x(), vec.y(), vec.z());
98 static TangentVector
Logmap(
const Q&
q, ChartJacobian
H = {}) {
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();
121 _Scalar angle = 2 *
acos(qw),
s =
sqrt(1 - qw * qw);
125 else if (angle < -
M_PI)
127 omega = (angle /
s) * q.vec();
130 _Scalar angle = 2 *
acos(-qw),
s =
sqrt(1 - qw * qw);
133 else if (angle < -
M_PI)
135 omega = (angle /
s) * -q.vec();
147 static TangentVector
Local(
const Q& g,
const Q& h,
148 ChartJacobian H1 = {}, ChartJacobian H2 = {}) {
151 TangentVector
v = Logmap(b, (H1 || H2) ? &D_v_b : 0);
152 if (H1) *H1 = D_v_b * (*H1);
153 if (H2) *H2 = D_v_b * (*H2);
157 static Q
Retract(
const Q& g,
const TangentVector&
v,
158 ChartJacobian H1 = {}, ChartJacobian H2 = {}) {
160 Q
b =
Expmap(v,H2 ? &D_h_v : 0);
161 Q h = Compose(g, b, H1, H2);
162 if (H2) *H2 = (*H2) * D_h_v;
169 static void Print(
const Q& q,
const std::string&
str =
"") {
171 std::cout <<
"Eigen::Quaternion: ";
173 std::cout <<
str <<
" ";
174 std::cout << q.vec().transpose() << std::endl;
176 static bool Equals(
const Q& q1,
const Q& q2,
double tol = 1
e-8) {
177 return Between(q1, q2).vec().array().abs().maxCoeff() <
tol;
Jet< T, N > cos(const Jet< T, N > &f)
static MatrixDD ExpmapDerivative(const TangentVector &omega)
Derivative of Expmap, currently only defined for SO3.
static Q Expmap(const Eigen::Ref< const TangentVector > &omega, ChartJacobian H={})
Exponential map, using the inlined code from Eigen's conversion from axis/angle.
tag to assert a type is a Lie group
OptionalJacobian< 3, 3 > ChartJacobian
QUATERNION_TYPE ManifoldType
static MatrixDD LogmapDerivative(const TangentVector &omega)
Derivative of Logmap, currently only defined for SO3.
Jet< T, N > acos(const Jet< T, N > &f)
Jet< T, N > sin(const Jet< T, N > &f)
Pose2_ Expmap(const Vector3_ &xi)
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)
static TangentVector Local(const Q &g, const Q &h, ChartJacobian H1={}, ChartJacobian H2={})
static EIGEN_DEVICE_FUNC Quaternion< Scalar > Identity()
static void Print(const Q &q, const std::string &str="")
lie_group_tag structure_category
Group operator syntax flavors.
static Q Compose(const Q &g, const Q &h, ChartJacobian Hg={}, ChartJacobian Hh={})
Array< int, Dynamic, 1 > v
BetweenFactor< Rot3 > Between
static bool Equals(const Q &q1, const Q &q2, double tol=1e-8)
Vector::Scalar omega(const Vector &t, const Vector &s, RealScalar angle)
Array< double, 1, 3 > e(1./3., 0.5, 2.)
EIGEN_DEVICE_FUNC const Scalar & q
static Q Between(const Q &g, const Q &h, ChartJacobian Hg={}, ChartJacobian Hh={})
Base class and basic functions for Lie types.
A matrix or vector expression mapping an existing expression.
multiplicative_group_tag group_flavor
The quaternion class used to represent 3D orientations and rotations.
static Q Inverse(const Q &g, ChartJacobian H={})
static Q Retract(const Q &g, const TangentVector &v, ChartJacobian H1={}, ChartJacobian H2={})
Jet< T, N > sqrt(const Jet< T, N > &f)
static TangentVector Logmap(const Q &q, ChartJacobian H={})
We use our own Logmap, as there is a slight bug in Eigen.
The matrix class, also used for vectors and row-vectors.
Eigen::Quaternion< double, Eigen::DontAlign > Quaternion