gtsam  4.0.0
gtsam
gtsam::Rot3 Class Reference
+ Inheritance diagram for gtsam::Rot3:

Constructors and named constructors

 Rot3 ()
 default constructor, unit rotation
 
 Rot3 (const Point3 &col1, const Point3 &col2, const Point3 &col3)
 Constructor from columns More...
 
 Rot3 (double R11, double R12, double R13, double R21, double R22, double R23, double R31, double R32, double R33)
 constructor from a rotation matrix, as doubles in row-major order !!!
 
template<typename Derived >
 Rot3 (const Eigen::MatrixBase< Derived > &R)
 Constructor from a rotation matrix Version for generic matrices. More...
 
 Rot3 (const Matrix3 &R)
 Constructor from a rotation matrix Overload version for Matrix3 to avoid casting in quaternion mode.
 
 Rot3 (const Quaternion &q)
 Constructor from a quaternion. More...
 
 Rot3 (double w, double x, double y, double z)
 
virtual ~Rot3 ()
 Virtual destructor.
 
static Rot3 Random (boost::mt19937 &rng)
 Random, generates a random axis, then random angle \in [-p,pi].
 
static Rot3 Rx (double t)
 Rotation around X axis as in http://en.wikipedia.org/wiki/Rotation_matrix, counterclockwise when looking from unchanging axis.
 
static Rot3 Ry (double t)
 Rotation around Y axis as in http://en.wikipedia.org/wiki/Rotation_matrix, counterclockwise when looking from unchanging axis.
 
static Rot3 Rz (double t)
 Rotation around Z axis as in http://en.wikipedia.org/wiki/Rotation_matrix, counterclockwise when looking from unchanging axis.
 
static Rot3 RzRyRx (double x, double y, double z)
 Rotations around Z, Y, then X axes as in http://en.wikipedia.org/wiki/Rotation_matrix, counterclockwise when looking from unchanging axis.
 
static Rot3 RzRyRx (const Vector &xyz)
 Rotations around Z, Y, then X axes as in http://en.wikipedia.org/wiki/Rotation_matrix, counterclockwise when looking from unchanging axis.
 
static Rot3 Yaw (double t)
 Positive yaw is to right (as in aircraft heading). See ypr.
 
static Rot3 Pitch (double t)
 Positive pitch is up (increasing aircraft altitude).See ypr.
 
static Rot3 Roll (double t)
 
static Rot3 Ypr (double y, double p, double r)
 Returns rotation nRb from body to nav frame. More...
 
static Rot3 Quaternion (double w, double x, double y, double z)
 Create from Quaternion coefficients.
 
static Rot3 AxisAngle (const Point3 &axis, double angle)
 Convert from axis/angle representation. More...
 
static Rot3 AxisAngle (const Unit3 &axis, double angle)
 Convert from axis/angle representation. More...
 
static Rot3 Rodrigues (const Vector3 &w)
 Rodrigues' formula to compute an incremental rotation. More...
 
static Rot3 Rodrigues (double wx, double wy, double wz)
 Rodrigues' formula to compute an incremental rotation. More...
 
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.
 
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.
 

Group

Rot3 operator * (const Rot3 &R2) const
 Syntatic sugar for composing two rotations.
 
Rot3 inverse () const
 inverse of a rotation, TODO should be different for M/Q
 
Rot3 conjugate (const Rot3 &cRb) const
 Conjugation: given a rotation acting in frame B, compute rotation c1Rc2 acting in a frame C. More...
 
static Rot3 identity ()
 identity rotation for group operation
 

Manifold

enum  CoordinatesMode { EXPMAP, CAYLEY }
 The method retract() is used to map from the tangent space back to the manifold. More...
 
Rot3 retractCayley (const Vector &omega) const
 Retraction from R^3 to Rot3 manifold using the Cayley transform.
 
Vector3 localCayley (const Rot3 &other) const
 Inverse of retractCayley.
 

Lie Group

Matrix3 AdjointMap () const
 Calculate Adjoint map.
 
static Rot3 Expmap (const Vector3 &v, OptionalJacobian< 3, 3 > H=boost::none)
 Exponential map at identity - create a rotation from canonical coordinates \( [R_x,R_y,R_z] \) using Rodrigues' formula.
 
static Vector3 Logmap (const Rot3 &R, OptionalJacobian< 3, 3 > H=boost::none)
 Log map at identity - returns the canonical coordinates \( [R_x,R_y,R_z] \) of this rotation.
 
static Matrix3 ExpmapDerivative (const Vector3 &x)
 Derivative of Expmap.
 
static Matrix3 LogmapDerivative (const Vector3 &x)
 Derivative of Logmap.
 

Advanced Interface

GTSAM_EXPORT friend std::ostream & operator<< (std::ostream &os, const Rot3 &p)
 Output stream operator.
 
gtsam::Quaternion toQuaternion () const
 Compute the quaternion representation of this rotation. More...
 
Vector quaternion () const
 Converts to a generic matrix to allow for use with matlab In format: w x y z.
 
Rot3 slerp (double t, const Rot3 &other) const
 Spherical Linear intERPolation between *this and other. More...
 

Public Member Functions

Testable
void print (const std::string &s="R") const
 print
 
bool equals (const Rot3 &p, double tol=1e-9) const
 equals with an tolerance
 
Group Action on Point3
Point3 rotate (const Point3 &p, OptionalJacobian< 3, 3 > H1=boost::none, OptionalJacobian< 3, 3 > H2=boost::none) const
 rotate point from rotated coordinate frame to world \( p^w = R_c^w p^c \)
 
Point3 operator * (const Point3 &p) const
 rotate point from rotated coordinate frame to world = R*p
 
Point3 unrotate (const Point3 &p, OptionalJacobian< 3, 3 > H1=boost::none, OptionalJacobian< 3, 3 > H2=boost::none) const
 rotate point from world to rotated frame \( p^c = (R_c^w)^T p^w \)
 
Group Action on Unit3
Unit3 rotate (const Unit3 &p, OptionalJacobian< 2, 3 > HR=boost::none, OptionalJacobian< 2, 2 > Hp=boost::none) const
 rotate 3D direction from rotated coordinate frame to world frame
 
Unit3 unrotate (const Unit3 &p, OptionalJacobian< 2, 3 > HR=boost::none, OptionalJacobian< 2, 2 > Hp=boost::none) const
 unrotate 3D direction from world frame to rotated coordinate frame
 
Unit3 operator * (const Unit3 &p) const
 rotate 3D direction from rotated coordinate frame to world frame
 
Standard Interface
Matrix3 matrix () const
 return 3*3 rotation matrix
 
Matrix3 transpose () const
 Return 3*3 transpose (inverse) rotation matrix.
 
Point3 column (int index) const
 
Point3 r1 () const
 first column
 
Point3 r2 () const
 second column
 
Point3 r3 () const
 third column
 
Vector3 xyz () const
 Use RQ to calculate xyz angle representation. More...
 
Vector3 ypr () const
 Use RQ to calculate yaw-pitch-roll angle representation. More...
 
Vector3 rpy () const
 Use RQ to calculate roll-pitch-yaw angle representation. More...
 
double roll () const
 Accessor to get to component of angle representations NOTE: these are not efficient to get to multiple separate parts, you should instead use xyz() or ypr() TODO: make this more efficient.
 
double pitch () const
 Accessor to get to component of angle representations NOTE: these are not efficient to get to multiple separate parts, you should instead use xyz() or ypr() TODO: make this more efficient.
 
double yaw () const
 Accessor to get to component of angle representations NOTE: these are not efficient to get to multiple separate parts, you should instead use xyz() or ypr() TODO: make this more efficient.
 
- Public Member Functions inherited from gtsam::LieGroup< Rot3, 3 >
 BOOST_STATIC_ASSERT_MSG (N !=Eigen::Dynamic, "LieGroup not yet specialized for dynamically sized types.")
 
const Rot3derived () const
 
Rot3 compose (const Rot3 &g) const
 
Rot3 compose (const Rot3 &g, ChartJacobian H1, ChartJacobian H2=boost::none) const
 
Rot3 between (const Rot3 &g) const
 
Rot3 between (const Rot3 &g, ChartJacobian H1, ChartJacobian H2=boost::none) const
 
Rot3 inverse (ChartJacobian H) const
 
Rot3 expmap (const TangentVector &v) const
 expmap as required by manifold concept Applies exponential map to v and composes with *this
 
Rot3 expmap (const TangentVector &v, ChartJacobian H1, ChartJacobian H2=boost::none) const
 expmap with optional derivatives
 
TangentVector logmap (const Rot3 &g) const
 logmap as required by manifold concept Applies logarithmic map to group element that takes *this to g
 
TangentVector logmap (const Rot3 &g, ChartJacobian H1, ChartJacobian H2=boost::none) const
 logmap with optional derivatives
 
Rot3 retract (const TangentVector &v) const
 retract as required by manifold concept: applies v at *this
 
Rot3 retract (const TangentVector &v, ChartJacobian H1, ChartJacobian H2=boost::none) const
 retract with optional derivatives
 
TangentVector localCoordinates (const Rot3 &g) const
 localCoordinates as required by manifold concept: finds tangent vector between *this and g
 
TangentVector localCoordinates (const Rot3 &g, ChartJacobian H1, ChartJacobian H2=boost::none) const
 localCoordinates with optional derivatives
 

Classes

struct  CayleyChart
 
struct  ChartAtOrigin
 

Friends

class boost::serialization::access
 Serialization function.
 

Additional Inherited Members

- Static Public Member Functions inherited from gtsam::LieGroup< Rot3, 3 >
static Rot3 Retract (const TangentVector &v)
 Retract at origin: possible in Lie group because it has an identity.
 
static Rot3 Retract (const TangentVector &v, ChartJacobian H)
 Retract at origin with optional derivative.
 
static TangentVector LocalCoordinates (const Rot3 &g)
 LocalCoordinates at origin: possible in Lie group because it has an identity.
 
static TangentVector LocalCoordinates (const Rot3 &g, ChartJacobian H)
 LocalCoordinates at origin with optional derivative.
 
- Public Types inherited from gtsam::LieGroup< Rot3, 3 >
enum  
 
typedef OptionalJacobian< N, N > ChartJacobian
 
typedef Eigen::Matrix< double, N, N > Jacobian
 
typedef Eigen::Matrix< double, N, 1 > TangentVector
 

Member Enumeration Documentation

◆ CoordinatesMode

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.

Constructor & Destructor Documentation

◆ Rot3() [1/3]

gtsam::Rot3::Rot3 ( const Point3 col1,
const Point3 col2,
const Point3 col3 
)

Constructor from columns

Parameters
r1X-axis of rotated frame
r2Y-axis of rotated frame
r3Z-axis of rotated frame

◆ Rot3() [2/3]

template<typename Derived >
gtsam::Rot3::Rot3 ( const Eigen::MatrixBase< Derived > &  R)
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

◆ Rot3() [3/3]

gtsam::Rot3::Rot3 ( const Quaternion q)

Constructor from a quaternion.

This can also be called using a plain Vector, due to implicit conversion from Vector to Quaternion

Parameters
qThe quaternion

Member Function Documentation

◆ AxisAngle() [1/2]

static Rot3 gtsam::Rot3::AxisAngle ( const Point3 axis,
double  angle 
)
inlinestatic

Convert from axis/angle representation.

Parameters
axiswis the rotation axis, unit length
anglerotation angle
Returns
incremental rotation

◆ AxisAngle() [2/2]

static Rot3 gtsam::Rot3::AxisAngle ( const Unit3 axis,
double  angle 
)
inlinestatic

Convert from axis/angle representation.

Parameters
axisis the rotation axis
anglerotation angle
Returns
incremental rotation

◆ column()

Point3 gtsam::Rot3::column ( int  index) const
Deprecated:
, this is base 1, and was just confusing

◆ conjugate()

Rot3 gtsam::Rot3::conjugate ( const Rot3 cRb) const
inline

Conjugation: given a rotation acting in frame B, compute rotation c1Rc2 acting in a frame C.

Parameters
cRbrotation from B frame to C frame
Returns
c1Rc2 = cRb * b1Rb2 * cRb'

◆ Rodrigues() [1/2]

static Rot3 gtsam::Rot3::Rodrigues ( const Vector3 &  w)
inlinestatic

Rodrigues' formula to compute an incremental rotation.

Parameters
wa vector of incremental roll,pitch,yaw
Returns
incremental rotation

◆ Rodrigues() [2/2]

static Rot3 gtsam::Rot3::Rodrigues ( double  wx,
double  wy,
double  wz 
)
inlinestatic

Rodrigues' formula to compute an incremental rotation.

Parameters
wxIncremental roll (about X)
wyIncremental pitch (about Y)
wzIncremental yaw (about Z)
Returns
incremental rotation

◆ rpy()

Vector3 gtsam::Rot3::rpy ( ) const

Use RQ to calculate roll-pitch-yaw angle representation.

Returns
a vector containing ypr s.t. R = Rot3::Ypr(y,p,r)

◆ slerp()

Rot3 gtsam::Rot3::slerp ( double  t,
const Rot3 other 
) const

Spherical Linear intERPolation between *this and other.

Parameters
sa value between 0 and 1
otherfinal point of iterpolation geodesic on manifold

◆ toQuaternion()

gtsam::Quaternion gtsam::Rot3::toQuaternion ( ) const

Compute the quaternion representation of this rotation.

Returns
The quaternion

◆ xyz()

Vector3 gtsam::Rot3::xyz ( ) const

Use RQ to calculate xyz angle representation.

Returns
a vector containing x,y,z s.t. R = Rot3::RzRyRx(x,y,z)

◆ Ypr()

static Rot3 gtsam::Rot3::Ypr ( double  y,
double  p,
double  r 
)
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).

◆ ypr()

Vector3 gtsam::Rot3::ypr ( ) const

Use RQ to calculate yaw-pitch-roll angle representation.

Returns
a vector containing ypr s.t. R = Rot3::Ypr(y,p,r)

The documentation for this class was generated from the following files: