Rot3 is a 3D rotation represented as a rotation matrix if the preprocessor symbol GTSAM_USE_QUATERNIONS is not defined, or as a quaternion if it is defined. More...
#include <Rot3.h>
Classes | |
struct | CayleyChart |
struct | ChartAtOrigin |
Public Member Functions | |
Testable | |
void | print (const std::string &s="") const |
bool | equals (const Rot3 &p, double tol=1e-9) const |
Group Action on Point3 | |
Point3 | rotate (const Point3 &p, OptionalJacobian< 3, 3 > H1={}, OptionalJacobian< 3, 3 > H2={}) const |
Point3 | operator* (const Point3 &p) const |
rotate point from rotated coordinate frame to world = R*p More... | |
Point3 | unrotate (const Point3 &p, OptionalJacobian< 3, 3 > H1={}, OptionalJacobian< 3, 3 > H2={}) const |
rotate point from world to rotated frame ![]() | |
Group Action on Unit3 | |
Unit3 | rotate (const Unit3 &p, OptionalJacobian< 2, 3 > HR={}, OptionalJacobian< 2, 2 > Hp={}) const |
rotate 3D direction from rotated coordinate frame to world frame More... | |
Unit3 | unrotate (const Unit3 &p, OptionalJacobian< 2, 3 > HR={}, OptionalJacobian< 2, 2 > Hp={}) const |
unrotate 3D direction from world frame to rotated coordinate frame More... | |
Unit3 | operator* (const Unit3 &p) const |
rotate 3D direction from rotated coordinate frame to world frame More... | |
Standard Interface | |
Matrix3 | matrix () const |
Matrix3 | transpose () const |
Point3 | r1 () const |
first column More... | |
Point3 | r2 () const |
second column More... | |
Point3 | r3 () const |
third column More... | |
Vector3 | xyz (OptionalJacobian< 3, 3 > H={}) const |
Vector3 | ypr (OptionalJacobian< 3, 3 > H={}) const |
Vector3 | rpy (OptionalJacobian< 3, 3 > H={}) const |
double | roll (OptionalJacobian< 1, 3 > H={}) const |
double | pitch (OptionalJacobian< 1, 3 > H={}) const |
double | yaw (OptionalJacobian< 1, 3 > H={}) const |
![]() | |
Rot3 | between (const Rot3 &g) const |
Rot3 | between (const Rot3 &g, ChartJacobian H1, ChartJacobian H2={}) const |
SOn | between (const SOn &g, DynamicJacobian H1, DynamicJacobian H2) const |
GTSAM_EXPORT SOn | between (const SOn &g, DynamicJacobian H1, DynamicJacobian H2) const |
Rot3 | compose (const Rot3 &g) const |
Rot3 | compose (const Rot3 &g, ChartJacobian H1, ChartJacobian H2={}) const |
SOn | compose (const SOn &g, DynamicJacobian H1, DynamicJacobian H2) const |
GTSAM_EXPORT SOn | compose (const SOn &g, DynamicJacobian H1, DynamicJacobian H2) const |
const Rot3 & | derived () const |
Rot3 | expmap (const TangentVector &v) const |
Rot3 | expmap (const TangentVector &v, ChartJacobian H1, ChartJacobian H2={}) const |
expmap with optional derivatives More... | |
Rot3 | inverse (ChartJacobian H) const |
TangentVector | localCoordinates (const Rot3 &g) const |
localCoordinates as required by manifold concept: finds tangent vector between *this and g More... | |
TangentVector | localCoordinates (const Rot3 &g, ChartJacobian H1, ChartJacobian H2={}) const |
localCoordinates with optional derivatives More... | |
TangentVector | logmap (const Rot3 &g) const |
TangentVector | logmap (const Rot3 &g, ChartJacobian H1, ChartJacobian H2={}) const |
logmap with optional derivatives More... | |
Rot3 | retract (const TangentVector &v) const |
retract as required by manifold concept: applies v at *this More... | |
Rot3 | retract (const TangentVector &v, ChartJacobian H1, ChartJacobian H2={}) const |
retract with optional derivatives More... | |
Private Attributes | |
SO3 | rot_ |
Constructors and named constructors | |
Rot3 () | |
Rot3 (const Point3 &col1, const Point3 &col2, const Point3 &col3) | |
Rot3 (double R11, double R12, double R13, double R21, double R22, double R23, double R31, double R32, double R33) | |
Construct from a rotation matrix, as doubles in row-major order !!! More... | |
template<typename Derived > | |
Rot3 (const Eigen::MatrixBase< Derived > &R) | |
Rot3 (const Matrix3 &R) | |
Rot3 (const SO3 &R) | |
Rot3 (const Quaternion &q) | |
Rot3 (double w, double x, double y, double z) | |
virtual | ~Rot3 () |
Rot3 | normalized () const |
static Rot3 | Random (std::mt19937 &rng) |
static Rot3 | Rx (double t) |
Rotation around X axis as in http://en.wikipedia.org/wiki/Rotation_matrix, counterclockwise when looking from unchanging axis. More... | |
static Rot3 | Ry (double t) |
Rotation around Y axis as in http://en.wikipedia.org/wiki/Rotation_matrix, counterclockwise when looking from unchanging axis. More... | |
static Rot3 | Rz (double t) |
Rotation around Z axis as in http://en.wikipedia.org/wiki/Rotation_matrix, counterclockwise when looking from unchanging axis. More... | |
static Rot3 | RzRyRx (double x, double y, double z, OptionalJacobian< 3, 1 > Hx={}, OptionalJacobian< 3, 1 > Hy={}, OptionalJacobian< 3, 1 > Hz={}) |
Rotations around Z, Y, then X axes as in http://en.wikipedia.org/wiki/Rotation_matrix, counterclockwise when looking from unchanging axis. More... | |
static Rot3 | RzRyRx (const Vector &xyz, OptionalJacobian< 3, 3 > H={}) |
Rotations around Z, Y, then X axes as in http://en.wikipedia.org/wiki/Rotation_matrix, counterclockwise when looking from unchanging axis. More... | |
static Rot3 | Yaw (double t) |
Positive yaw is to right (as in aircraft heading). See ypr. More... | |
static Rot3 | Pitch (double t) |
Positive pitch is up (increasing aircraft altitude).See ypr. More... | |
static Rot3 | Roll (double t) |
static Rot3 | Ypr (double y, double p, double r, OptionalJacobian< 3, 1 > Hy={}, OptionalJacobian< 3, 1 > Hp={}, OptionalJacobian< 3, 1 > Hr={}) |
static Rot3 | Quaternion (double w, double x, double y, double z) |
static Rot3 | AxisAngle (const Point3 &axis, double angle) |
static Rot3 | AxisAngle (const Unit3 &axis, double angle) |
static Rot3 | Rodrigues (const Vector3 &w) |
static Rot3 | Rodrigues (double wx, double wy, double wz) |
static Rot3 | AlignPair (const Unit3 &axis, const Unit3 &a_p, const Unit3 &b_p) |
Determine a rotation to bring two vectors into alignment, using the rotation axis provided. More... | |
static Rot3 | AlignTwoPairs (const Unit3 &a_p, const Unit3 &b_p, const Unit3 &a_q, const Unit3 &b_q) |
Calculate rotation from two pairs of homogeneous points using two successive rotations. More... | |
static Rot3 | ClosestTo (const Matrix3 &M) |
Group | |
Rot3 | operator* (const Rot3 &R2) const |
Syntatic sugar for composing two rotations. More... | |
Rot3 | inverse () const |
inverse of a rotation More... | |
Rot3 | conjugate (const Rot3 &cRb) const |
static Rot3 | Identity () |
identity rotation for group operation More... | |
Manifold | |
enum | CoordinatesMode { EXPMAP, CAYLEY } |
Rot3 | retractCayley (const Vector &omega) const |
Retraction from R^3 to Rot3 manifold using the Cayley transform. More... | |
Vector3 | localCayley (const Rot3 &other) const |
Inverse of retractCayley. More... | |
Lie Group | |
using | LieAlgebra = Matrix3 |
Matrix3 | AdjointMap () const |
static Rot3 | Expmap (const Vector3 &v, OptionalJacobian< 3, 3 > H={}) |
static Vector3 | Logmap (const Rot3 &R, OptionalJacobian< 3, 3 > H={}) |
static Matrix3 | ExpmapDerivative (const Vector3 &x) |
Derivative of Expmap. More... | |
static Matrix3 | LogmapDerivative (const Vector3 &x) |
Derivative of Logmap. More... | |
static Matrix3 | Hat (const Vector3 &xi) |
Hat maps from tangent vector to Lie algebra. More... | |
static Vector3 | Vee (const Matrix3 &X) |
Vee maps from Lie algebra to tangent vector. More... | |
Advanced Interface | |
std::pair< Unit3, double > | axisAngle () const |
gtsam::Quaternion | toQuaternion () const |
Rot3 | slerp (double t, const Rot3 &other) const |
Spherical Linear intERPolation between *this and other. More... | |
Vector9 | vec (OptionalJacobian< 9, 3 > H={}) const |
Vee maps from Lie algebra to tangent vector. More... | |
GTSAM_EXPORT friend std::ostream & | operator<< (std::ostream &os, const Rot3 &p) |
Output stream operator. More... | |
Additional Inherited Members | |
![]() | |
typedef OptionalJacobian< N, N > | ChartJacobian |
typedef Eigen::Matrix< double, N, N > | Jacobian |
typedef Eigen::Matrix< double, N, 1 > | TangentVector |
![]() | |
static TangentVector | LocalCoordinates (const Rot3 &g) |
LocalCoordinates at origin: possible in Lie group because it has an identity. More... | |
static TangentVector | LocalCoordinates (const Rot3 &g, ChartJacobian H) |
LocalCoordinates at origin with optional derivative. More... | |
static Rot3 | Retract (const TangentVector &v) |
Retract at origin: possible in Lie group because it has an identity. More... | |
static Rot3 | Retract (const TangentVector &v, ChartJacobian H) |
Retract at origin with optional derivative. More... | |
![]() | |
constexpr static auto | dimension |
Rot3 is a 3D rotation represented as a rotation matrix if the preprocessor symbol GTSAM_USE_QUATERNIONS is not defined, or as a quaternion if it is defined.
using gtsam::Rot3::LieAlgebra = Matrix3 |
The method retract() is used to map from the tangent space back to the manifold. Its inverse, is localCoordinates(). For Lie groups, an obvious retraction is the exponential map, but this can be expensive to compute. The following Enum is used to indicate which method should be used. The default is determined by ROT3_DEFAULT_COORDINATES_MODE, which may be set at compile time, and itself defaults to Rot3::CAYLEY, or if GTSAM_USE_QUATERNIONS is defined, to Rot3::EXPMAP.
Enumerator | |
---|---|
EXPMAP | Use the Lie group exponential map to retract. |
CAYLEY | Retract and localCoordinates using the Cayley transform. |
gtsam::Rot3::Rot3 | ( | double | R11, |
double | R12, | ||
double | R13, | ||
double | R21, | ||
double | R22, | ||
double | R23, | ||
double | R31, | ||
double | R32, | ||
double | R33 | ||
) |
|
inlineexplicit |
Constructor from a rotation matrix Version for generic matrices. Need casting to Matrix3 in quaternion mode, since Eigen's quaternion doesn't allow assignment/construction from a generic matrix. See: http://stackoverflow.com/questions/27094132/cannot-understand-if-this-is-circular-dependency-or-clang#tab-top
|
inlineexplicit |
|
inlineexplicit |
gtsam::Rot3::Rot3 | ( | const Quaternion & | q | ) |
|
inline |
|
inlinevirtual |
|
inline |
pair< Unit3, double > gtsam::Rot3::axisAngle | ( | ) | const |
Compute the Euler axis and angle (in radians) representation of this rotation. The angle is in the range [0, π]. If the angle is not in the range, the axis is flipped around accordingly so that the returned angle is within the specified range.
|
inlinestatic |
Static, named constructor that finds Rot3 element closest to M in Frobenius norm.
Uses Full SVD to compute the orthogonal matrix, thus is highly accurate and robust.
N. J. Higham. Matrix nearness problems and applications. In M. J. C. Gover and S. Barnett, editors, Applications of Matrix Theory, pages 1–27. Oxford University Press, 1989.
|
inlinestatic |
|
static |
|
inlinestatic |
|
inlinestatic |
|
inline |
|
static |
|
static |
Matrix3 gtsam::Rot3::matrix | ( | ) | const |
Rot3 gtsam::Rot3::normalized | ( | ) | const |
Normalize rotation so that its determinant is 1. This means either re-orthogonalizing the Matrix representation or normalizing the quaternion representation.
This method is akin to ClosestTo
but uses a computationally cheaper algorithm.
Ref: https://drive.google.com/file/d/0B9rLLz1XQKmaZTlQdV81QjNoZTA/view
Implementation from here: https://stackoverflow.com/a/23082112/1236990
Essentially, this computes the orthogonalization error, distributes the error to the x and y rows, and then performs a Taylor expansion to orthogonalize.
|
inlinestatic |
double gtsam::Rot3::pitch | ( | OptionalJacobian< 1, 3 > | H = {} | ) | const |
void gtsam::Rot3::print | ( | const std::string & | s = "" | ) | const |
|
inlinestatic |
|
static |
|
inlinestatic |
double gtsam::Rot3::roll | ( | OptionalJacobian< 1, 3 > | H = {} | ) | const |
Point3 gtsam::Rot3::rotate | ( | const Point3 & | p, |
OptionalJacobian< 3, 3 > | H1 = {} , |
||
OptionalJacobian< 3, 3 > | H2 = {} |
||
) | const |
Unit3 gtsam::Rot3::rotate | ( | const Unit3 & | p, |
OptionalJacobian< 2, 3 > | HR = {} , |
||
OptionalJacobian< 2, 2 > | Hp = {} |
||
) | const |
Vector3 gtsam::Rot3::rpy | ( | OptionalJacobian< 3, 3 > | H = {} | ) | const |
|
static |
Rotation around X axis as in http://en.wikipedia.org/wiki/Rotation_matrix, counterclockwise when looking from unchanging axis.
|
static |
Rotation around Y axis as in http://en.wikipedia.org/wiki/Rotation_matrix, counterclockwise when looking from unchanging axis.
|
static |
Rotation around Z axis as in http://en.wikipedia.org/wiki/Rotation_matrix, counterclockwise when looking from unchanging axis.
|
inlinestatic |
Rotations around Z, Y, then X axes as in http://en.wikipedia.org/wiki/Rotation_matrix, counterclockwise when looking from unchanging axis.
|
static |
Rotations around Z, Y, then X axes as in http://en.wikipedia.org/wiki/Rotation_matrix, counterclockwise when looking from unchanging axis.
gtsam::Quaternion gtsam::Rot3::toQuaternion | ( | ) | const |
Matrix3 gtsam::Rot3::transpose | ( | ) | const |
Point3 gtsam::Rot3::unrotate | ( | const Point3 & | p, |
OptionalJacobian< 3, 3 > | H1 = {} , |
||
OptionalJacobian< 3, 3 > | H2 = {} |
||
) | const |
Unit3 gtsam::Rot3::unrotate | ( | const Unit3 & | p, |
OptionalJacobian< 2, 3 > | HR = {} , |
||
OptionalJacobian< 2, 2 > | Hp = {} |
||
) | const |
|
inline |
|
inlinestatic |
Vector3 gtsam::Rot3::xyz | ( | OptionalJacobian< 3, 3 > | H = {} | ) | const |
|
inlinestatic |
double gtsam::Rot3::yaw | ( | OptionalJacobian< 1, 3 > | H = {} | ) | const |
|
inlinestatic |
Returns rotation nRb from body to nav frame. For vehicle coordinate frame X forward, Y right, Z down: Positive yaw is to right (as in aircraft heading). Positive pitch is up (increasing aircraft altitude). Positive roll is to right (increasing yaw in aircraft). Tait-Bryan system from Spatial Reference Model (SRM) (x,y,z) = (roll,pitch,yaw) as described in http://www.sedris.org/wg8home/Documents/WG80462.pdf.
For vehicle coordinate frame X forward, Y left, Z up: Positive yaw is to left (as in aircraft heading). Positive pitch is down (decreasing aircraft altitude). Positive roll is to right (decreasing yaw in aircraft).
Vector3 gtsam::Rot3::ypr | ( | OptionalJacobian< 3, 3 > | H = {} | ) | const |
|
friend |
Output stream operator.