21 #include <gtsam/base/concepts.h> 26 #define QUATERNION_TYPE Eigen::Quaternion<_Scalar,_Options> 31 template<
typename _Scalar,
int _Options>
33 typedef QUATERNION_TYPE ManifoldType;
34 typedef QUATERNION_TYPE Q;
52 typedef Eigen::Matrix<_Scalar, 3, 1, _Options, 3, 1> TangentVector;
57 static Q Compose(
const Q &g,
const Q & h,
59 if (Hg) *Hg = h.toRotationMatrix().transpose();
64 static Q Between(
const Q &g,
const Q & h,
66 Q d = g.inverse() * h;
67 if (Hg) *Hg = -d.toRotationMatrix().transpose();
72 static Q Inverse(
const Q &g,
74 if (H) *H = -g.toRotationMatrix();
79 static Q
Expmap(
const Eigen::Ref<const TangentVector>& omega,
84 _Scalar theta2 = omega.dot(omega);
85 if (theta2 > std::numeric_limits<_Scalar>::epsilon()) {
86 _Scalar theta = std::sqrt(theta2);
87 _Scalar ha = _Scalar(0.5) * theta;
88 Vector3 vec = (sin(ha) / theta) * omega;
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());
103 static const double twoPi = 2.0 * M_PI, NearlyOne = 1.0 - 1e-10,
104 NearlyNegativeOne = -1.0 + 1e-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) {
139 Q b = Between(g, h, H1, H2);
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);
147 static Q Retract(
const Q& g,
const TangentVector& v,
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;
166 static bool Equals(
const Q& q1,
const Q& q2,
double tol = 1e-8) {
167 return Between(q1, q2).vec().array().abs().maxCoeff() < tol;
172 typedef Eigen::Quaternion<double, Eigen::DontAlign> Quaternion;
Group operator syntax flavors.
Definition: Group.h:37
3*3 matrix representation of SO(3)
OptionalJacobian is an Eigen::Ref like class that can take be constructed using either a fixed size o...
Definition: OptionalJacobian.h:39
A manifold defines a space in which there is a notion of a linear tangent space that can be centered ...
Definition: concepts.h:30
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.
Definition: Quaternion.h:79
tag to assert a type is a Lie group
Definition: Lie.h:167
Global functions in a separate testing namespace.
Definition: chartTesting.h:28
Base class and basic functions for Lie types.
static Matrix3 LogmapDerivative(const Vector3 &omega)
Derivative of Logmap.
Definition: SO3.cpp:182
static Matrix3 ExpmapDerivative(const Vector3 &omega)
Derivative of Expmap.
Definition: SO3.cpp:134
static TangentVector Logmap(const Q &q, ChartJacobian H=boost::none)
We use our own Logmap, as there is a slight bug in Eigen.
Definition: Quaternion.h:98