26#include <gtsam/geometry/Unit3.h>
29#include <gtsam/base/concepts.h>
30#include <gtsam/config.h>
35#ifndef ROT3_DEFAULT_COORDINATES_MODE
36 #ifdef GTSAM_USE_QUATERNIONS
38 #define ROT3_DEFAULT_COORDINATES_MODE Rot3::EXPMAP
41 #ifndef GTSAM_ROT3_EXPMAP
43 #define ROT3_DEFAULT_COORDINATES_MODE Rot3::CAYLEY
45 #define ROT3_DEFAULT_COORDINATES_MODE Rot3::EXPMAP
63#ifdef GTSAM_USE_QUATERNIONS
65 gtsam::Quaternion quaternion_;
87 Rot3(
double R11,
double R12,
double R13,
88 double R21,
double R22,
double R23,
89 double R31,
double R32,
double R33);
98 template <
typename Derived>
99#ifdef GTSAM_USE_QUATERNIONS
100 explicit Rot3(
const Eigen::MatrixBase<Derived>& R) {
101 quaternion_ = Matrix3(R);
104 explicit Rot3(
const Eigen::MatrixBase<Derived>& R) : rot_(R) {
112#ifdef GTSAM_USE_QUATERNIONS
113 explicit Rot3(
const Matrix3& R) : quaternion_(R) {}
115 explicit Rot3(
const Matrix3& R) : rot_(R) {}
121#ifdef GTSAM_USE_QUATERNIONS
122 explicit Rot3(
const SO3& R) : quaternion_(R.matrix()) {}
131 Rot3(
const Quaternion& q);
132 Rot3(
double w,
double x,
double y,
double z) :
Rot3(Quaternion(w, x, y, z)) {}
140 static Rot3 Random(std::mt19937 & rng);
148 static Rot3 Rx(
double t);
151 static Rot3 Ry(
double t);
154 static Rot3 Rz(
double t);
157 static Rot3 RzRyRx(
double x,
double y,
double z,
165 assert(xyz.size() == 3);
169 out = RzRyRx(xyz(0), xyz(1), xyz(2), Hx, Hy, Hz);
172 out = RzRyRx(xyz(0), xyz(1), xyz(2));
183 static Rot3 Roll (
double t) {
return Rx(t); }
203 return RzRyRx(r, p, y, Hr, Hp, Hy);
208 gtsam::Quaternion q(w, x, y, z);
221#ifdef GTSAM_USE_QUATERNIONS
222 return gtsam::Quaternion(Eigen::AngleAxis<double>(angle, unitAxis));
255 return Rodrigues(Vector3(wx, wy, wz));
286 Rot3 normalized()
const;
293 void print(
const std::string& s=
"")
const;
296 bool equals(
const Rot3& p,
double tol = 1e-9)
const;
312#ifdef GTSAM_USE_QUATERNIONS
313 return Rot3(quaternion_.inverse());
326 return cRb * (*this) * cRb.
inverse();
344#ifndef GTSAM_USE_QUATERNIONS
349#ifndef GTSAM_USE_QUATERNIONS
359 return compose(CayleyChart::Retract(omega));
364 return CayleyChart::Local(between(other));
379#ifdef GTSAM_USE_QUATERNIONS
393 static Matrix3 ExpmapDerivative(
const Vector3& x);
396 static Matrix3 LogmapDerivative(
const Vector3& x);
403 static Rot3 Retract(
const Vector3& v, ChartJacobian H = boost::none);
404 static Vector3 Local(
const Rot3& r, ChartJacobian H = boost::none);
446 Matrix3 matrix()
const;
451 Matrix3 transpose()
const;
514 std::pair<Unit3, double> axisAngle()
const;
519 gtsam::Quaternion toQuaternion()
const;
525 Vector quaternion()
const;
532 Rot3 slerp(
double t,
const Rot3& other)
const;
535 GTSAM_EXPORT
friend std::ostream &operator<<(std::ostream &os,
const Rot3& p);
541 friend class boost::serialization::access;
542 template <
class ARCHIVE>
543 void serialize(ARCHIVE& ar,
const unsigned int ) {
544#ifndef GTSAM_USE_QUATERNIONS
546 ar& boost::serialization::make_nvp(
"rot11", M(0, 0));
547 ar& boost::serialization::make_nvp(
"rot12", M(0, 1));
548 ar& boost::serialization::make_nvp(
"rot13", M(0, 2));
549 ar& boost::serialization::make_nvp(
"rot21", M(1, 0));
550 ar& boost::serialization::make_nvp(
"rot22", M(1, 1));
551 ar& boost::serialization::make_nvp(
"rot23", M(1, 2));
552 ar& boost::serialization::make_nvp(
"rot31", M(2, 0));
553 ar& boost::serialization::make_nvp(
"rot32", M(2, 1));
554 ar& boost::serialization::make_nvp(
"rot33", M(2, 2));
556 ar& boost::serialization::make_nvp(
"w", quaternion_.w());
557 ar& boost::serialization::make_nvp(
"x", quaternion_.x());
558 ar& boost::serialization::make_nvp(
"y", quaternion_.y());
559 ar& boost::serialization::make_nvp(
"z", quaternion_.z());
563#ifdef GTSAM_USE_QUATERNIONS
580 GTSAM_EXPORT std::pair<Matrix3, Vector3>
RQ(
581 const Matrix3& A, OptionalJacobian<3, 9> H = boost::none);
#define GTSAM_MAKE_ALIGNED_OPERATOR_NEW
This marks a GTSAM object to require alignment.
Definition: types.h:277
Lie Group wrapper for Eigen Quaternions.
3*3 matrix representation of SO(3)
Global functions in a separate testing namespace.
Definition: chartTesting.h:28
std::string serialize(const T &input)
serializes to a string
Definition: serialization.h:112
pair< Matrix3, Vector3 > RQ(const Matrix3 &A, OptionalJacobian< 3, 9 > H)
[RQ] receives a 3 by 3 matrix and returns an upper triangular matrix R and 3 rotation angles correspo...
Definition: Rot3.cpp:258
void print(const Matrix &A, const string &s, ostream &stream)
print without optional string, must specify cout yourself
Definition: Matrix.cpp:155
const MATRIX::ConstColXpr column(const MATRIX &A, size_t j)
Extracts a column view from a matrix that avoids a copy.
Definition: Matrix.h:214
Point2 operator*(double s, const Point2 &p)
multiply with scalar
Definition: Point2.h:47
Vector3 Point3
As of GTSAM 4, in order to make GTSAM more lean, it is now possible to just typedef Point3 to Vector3...
Definition: Point3.h:35
A manifold defines a space in which there is a notion of a linear tangent space that can be centered ...
Definition: concepts.h:30
A CRTP helper class that implements Lie group methods Prerequisites: methods operator*,...
Definition: Lie.h:37
Both LieGroupTraits and Testable.
Definition: Lie.h:229
OptionalJacobian is an Eigen::Ref like class that can take be constructed using either a fixed size o...
Definition: OptionalJacobian.h:39
Template to create a binary predicate.
Definition: Testable.h:111
Rot3 retractCayley(const Vector &omega) const
Retraction from R^3 to Rot3 manifold using the Cayley transform.
Definition: Rot3.h:358
Matrix3 AdjointMap() const
Calculate Adjoint map.
Definition: Rot3.h:399
static Rot3 ClosestTo(const Matrix3 &M)
Static, named constructor that finds Rot3 element closest to M in Frobenius norm.
Definition: Rot3.h:274
virtual ~Rot3()
Virtual destructor.
Definition: Rot3.h:143
static Rot3 Yaw(double t)
Positive yaw is to right (as in aircraft heading). See ypr.
Definition: Rot3.h:177
static Rot3 AxisAngle(const Unit3 &axis, double angle)
Convert from axis/angle representation.
Definition: Rot3.h:234
Rot3(const Matrix3 &R)
Constructor from a rotation matrix Overload version for Matrix3 to avoid casting in quaternion mode.
Definition: Rot3.h:115
static Rot3 Rodrigues(const Vector3 &w)
Rodrigues' formula to compute an incremental rotation.
Definition: Rot3.h:243
static Rot3 AxisAngle(const Point3 &axis, double angle)
Convert from axis/angle representation.
Definition: Rot3.h:218
static Rot3 Pitch(double t)
Positive pitch is up (increasing aircraft altitude).See ypr.
Definition: Rot3.h:180
static Rot3 RzRyRx(const Vector &xyz, OptionalJacobian< 3, 3 > H=boost::none)
Rotations around Z, Y, then X axes as in http://en.wikipedia.org/wiki/Rotation_matrix,...
Definition: Rot3.h:163
Vector3 localCayley(const Rot3 &other) const
Inverse of retractCayley.
Definition: Rot3.h:363
static Rot3 Quaternion(double w, double x, double y, double z)
Create from Quaternion coefficients.
Definition: Rot3.h:207
static Rot3 identity()
identity rotation for group operation
Definition: Rot3.h:303
Rot3 conjugate(const Rot3 &cRb) const
Conjugation: given a rotation acting in frame B, compute rotation c1Rc2 acting in a frame C.
Definition: Rot3.h:324
static Rot3 Rodrigues(double wx, double wy, double wz)
Rodrigues' formula to compute an incremental rotation.
Definition: Rot3.h:254
Rot3 inverse() const
inverse of a rotation
Definition: Rot3.h:311
Rot3(const SO3 &R)
Constructor from an SO3 instance.
Definition: Rot3.h:124
static Rot3 Expmap(const Vector3 &v, OptionalJacobian< 3, 3 > H=boost::none)
Exponential map at identity - create a rotation from canonical coordinates using Rodrigues' formula.
Definition: Rot3.h:377
static Matrix3 ExpmapDerivative(const Vector3 &x)
Derivative of Expmap.
Definition: Rot3.cpp:248
static Rot3 Ypr(double y, double p, double r, OptionalJacobian< 3, 1 > Hy=boost::none, OptionalJacobian< 3, 1 > Hp=boost::none, OptionalJacobian< 3, 1 > Hr=boost::none)
Returns rotation nRb from body to nav frame.
Definition: Rot3.h:199
CoordinatesMode
The method retract() is used to map from the tangent space back to the manifold.
Definition: Rot3.h:342
@ CAYLEY
Retract and localCoordinates using the Cayley transform.
Definition: Rot3.h:345
@ EXPMAP
Use the Lie group exponential map to retract.
Definition: Rot3.h:343
Rot3(const Eigen::MatrixBase< Derived > &R)
Constructor from a rotation matrix Version for generic matrices.
Definition: Rot3.h:104
MatrixNN matrix_
Rotation matrix.
Definition: SOn.h:60
static SO AxisAngle(const Vector3 &axis, double theta)
Constructor from axis and angle. Only defined for SO3.
const MatrixNN & matrix() const
Return matrix.
Definition: SOn.h:152
static SO ClosestTo(const MatrixNN &M)
Named constructor that finds SO(n) matrix closest to M in Frobenius norm, currently only defined for ...
Represents a 3D point on a unit sphere.
Definition: Unit3.h:42
GTSAM_EXPORT Vector3 unitVector(OptionalJacobian< 3, 2 > H=boost::none) const
Return unit-norm Vector.
Definition: Unit3.cpp:143