Classes | Private Member Functions | Private Attributes | Friends | List of all members
gtsam::Rot3 Class Reference

#include <Rot3.h>

Inheritance diagram for gtsam::Rot3:
Inheritance graph
[legend]

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=boost::none, OptionalJacobian< 3, 3 > H2=boost::none) 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=boost::none, OptionalJacobian< 3, 3 > H2=boost::none) const
 rotate point from world to rotated frame $ p^c = (R_c^w)^T p^w $ More...
 
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 More...
 
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 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 column (int index) 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=boost::none) const
 
Vector3 ypr (OptionalJacobian< 3, 3 > H=boost::none) const
 
Vector3 rpy (OptionalJacobian< 3, 3 > H=boost::none) const
 
double roll (OptionalJacobian< 1, 3 > H=boost::none) const
 
double pitch (OptionalJacobian< 1, 3 > H=boost::none) const
 
double yaw (OptionalJacobian< 1, 3 > H=boost::none) const
 
- Public Member Functions inherited from gtsam::LieGroup< Rot3, 3 >
Rot3 between (const Rot3 &g) const
 
Rot3 between (const Rot3 &g, ChartJacobian H1, ChartJacobian H2=boost::none) const
 
Rot3 compose (const Rot3 &g) const
 
Rot3 compose (const Rot3 &g, ChartJacobian H1, ChartJacobian H2=boost::none) const
 
const Rot3derived () const
 
Rot3 expmap (const TangentVector &v) const
 
Rot3 expmap (const TangentVector &v, ChartJacobian H1, ChartJacobian H2=boost::none) 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=boost::none) const
 localCoordinates with optional derivatives More...
 
TangentVector logmap (const Rot3 &g) const
 
TangentVector logmap (const Rot3 &g, ChartJacobian H1, ChartJacobian H2=boost::none) 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=boost::none) const
 retract with optional derivatives More...
 

Private Member Functions

template<class ARCHIVE >
void serialize (ARCHIVE &ar, const unsigned int)
 

Private Attributes

SO3 rot_
 

Friends

class boost::serialization::access
 

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)
 
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=boost::none, OptionalJacobian< 3, 1 > Hy=boost::none, OptionalJacobian< 3, 1 > Hz=boost::none)
 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=boost::none)
 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=boost::none, OptionalJacobian< 3, 1 > Hp=boost::none, OptionalJacobian< 3, 1 > Hr=boost::none)
 
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

Matrix3 AdjointMap () const
 
static Rot3 Expmap (const Vector3 &v, OptionalJacobian< 3, 3 > H=boost::none)
 
static Vector3 Logmap (const Rot3 &R, OptionalJacobian< 3, 3 > H=boost::none)
 
static Matrix3 ExpmapDerivative (const Vector3 &x)
 Derivative of Expmap. More...
 
static Matrix3 LogmapDerivative (const Vector3 &x)
 Derivative of Logmap. More...
 

Advanced Interface

GTSAM_EXPORT friend std::ostream & operator<< (std::ostream &os, const Rot3 &p)
 Output stream operator. More...
 
std::pair< Unit3, double > axisAngle () const
 
gtsam::Quaternion toQuaternion () const
 
Vector quaternion () const
 
Rot3 slerp (double t, const Rot3 &other) const
 Spherical Linear intERPolation between *this and other. More...
 

Additional Inherited Members

- Public Types inherited from gtsam::LieGroup< Rot3, 3 >
enum  
 
typedef OptionalJacobian< N, NChartJacobian
 
typedef Eigen::Matrix< double, N, NJacobian
 
typedef Eigen::Matrix< double, N, 1 > TangentVector
 
- Static Public Member Functions inherited from gtsam::LieGroup< Rot3, 3 >
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...
 

Detailed Description

Definition at line 59 of file Rot3.h.

Member Enumeration Documentation

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.

Definition at line 342 of file Rot3.h.

Constructor & Destructor Documentation

gtsam::Rot3::Rot3 ( )

default constructor, unit rotation

Definition at line 35 of file Rot3M.cpp.

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

Definition at line 38 of file Rot3M.cpp.

gtsam::Rot3::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 !!!

Definition at line 45 of file Rot3M.cpp.

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

Definition at line 104 of file Rot3.h.

gtsam::Rot3::Rot3 ( const Matrix3 &  R)
inlineexplicit

Constructor from a rotation matrix Overload version for Matrix3 to avoid casting in quaternion mode.

Definition at line 115 of file Rot3.h.

gtsam::Rot3::Rot3 ( const SO3 R)
inlineexplicit

Constructor from an SO3 instance

Definition at line 124 of file Rot3.h.

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

Definition at line 53 of file Rot3M.cpp.

gtsam::Rot3::Rot3 ( double  w,
double  x,
double  y,
double  z 
)
inline

Definition at line 132 of file Rot3.h.

virtual gtsam::Rot3::~Rot3 ( )
inlinevirtual

Virtual destructor

Definition at line 143 of file Rot3.h.

Member Function Documentation

Matrix3 gtsam::Rot3::AdjointMap ( ) const
inline

Calculate Adjoint map

Definition at line 399 of file Rot3.h.

Rot3 gtsam::Rot3::AlignPair ( const Unit3 axis,
const Unit3 a_p,
const Unit3 b_p 
)
static

Determine a rotation to bring two vectors into alignment, using the rotation axis provided.

Definition at line 50 of file Rot3.cpp.

Rot3 gtsam::Rot3::AlignTwoPairs ( const Unit3 a_p,
const Unit3 b_p,
const Unit3 a_q,
const Unit3 b_q 
)
static

Calculate rotation from two pairs of homogeneous points using two successive rotations.

Definition at line 74 of file Rot3.cpp.

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

Convert from axis/angle representation

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

Definition at line 218 of file Rot3.h.

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

Definition at line 234 of file Rot3.h.

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.

Returns
pair consisting of Unit3 axis and angle in radians

Definition at line 242 of file Rot3.cpp.

static Rot3 gtsam::Rot3::ClosestTo ( const Matrix3 &  M)
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.

Definition at line 274 of file Rot3.h.

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

Definition at line 149 of file Rot3.cpp.

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'

Definition at line 324 of file Rot3.h.

bool gtsam::Rot3::equals ( const Rot3 p,
double  tol = 1e-9 
) const

equals with an tolerance

Definition at line 100 of file Rot3.cpp.

static Rot3 gtsam::Rot3::Expmap ( const Vector3 v,
OptionalJacobian< 3, 3 >  H = boost::none 
)
inlinestatic

Exponential map at identity - create a rotation from canonical coordinates $ [R_x,R_y,R_z] $ using Rodrigues' formula

Definition at line 377 of file Rot3.h.

Matrix3 gtsam::Rot3::ExpmapDerivative ( const Vector3 x)
static

Derivative of Expmap.

Definition at line 248 of file Rot3.cpp.

static Rot3 gtsam::Rot3::identity ( )
inlinestatic

identity rotation for group operation

Definition at line 303 of file Rot3.h.

Rot3 gtsam::Rot3::inverse ( ) const
inline

inverse of a rotation

Definition at line 311 of file Rot3.h.

Vector3 gtsam::Rot3::localCayley ( const Rot3 other) const
inline

Inverse of retractCayley.

Definition at line 363 of file Rot3.h.

Vector3 gtsam::Rot3::Logmap ( const Rot3 R,
OptionalJacobian< 3, 3 >  H = boost::none 
)
static

Log map at identity - returns the canonical coordinates $ [R_x,R_y,R_z] $ of this rotation

Definition at line 158 of file Rot3M.cpp.

Matrix3 gtsam::Rot3::LogmapDerivative ( const Vector3 x)
static

Derivative of Logmap.

Definition at line 253 of file Rot3.cpp.

Matrix3 gtsam::Rot3::matrix ( ) const

return 3*3 rotation matrix

Definition at line 219 of file Rot3M.cpp.

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.

Definition at line 112 of file Rot3M.cpp.

Rot3 gtsam::Rot3::operator* ( const Rot3 R2) const

Syntatic sugar for composing two rotations.

Definition at line 139 of file Rot3M.cpp.

Point3 gtsam::Rot3::operator* ( const Point3 p) const

rotate point from rotated coordinate frame to world = R*p

Definition at line 105 of file Rot3.cpp.

Unit3 gtsam::Rot3::operator* ( const Unit3 p) const

rotate 3D direction from rotated coordinate frame to world frame

Definition at line 130 of file Rot3.cpp.

static Rot3 gtsam::Rot3::Pitch ( double  t)
inlinestatic

Positive pitch is up (increasing aircraft altitude).See ypr.

Definition at line 180 of file Rot3.h.

double gtsam::Rot3::pitch ( OptionalJacobian< 1, 3 >  H = boost::none) 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

Definition at line 207 of file Rot3.cpp.

void gtsam::Rot3::print ( const std::string &  s = "") const

print

Definition at line 34 of file Rot3.cpp.

static Rot3 gtsam::Rot3::Quaternion ( double  w,
double  x,
double  y,
double  z 
)
inlinestatic

Create from Quaternion coefficients

Definition at line 207 of file Rot3.h.

Vector gtsam::Rot3::quaternion ( ) const

Converts to a generic matrix to allow for use with matlab In format: w x y z

Definition at line 231 of file Rot3.cpp.

Point3 gtsam::Rot3::r1 ( ) const

first column

Definition at line 224 of file Rot3M.cpp.

Point3 gtsam::Rot3::r2 ( ) const

second column

Definition at line 227 of file Rot3M.cpp.

Point3 gtsam::Rot3::r3 ( ) const

third column

Definition at line 230 of file Rot3M.cpp.

Rot3 gtsam::Rot3::Random ( std::mt19937 &  rng)
static

Random, generates a random axis, then random angle [-p,pi] Example: std::mt19937 engine(42); Unit3 unit = Unit3::Random(engine);

Definition at line 40 of file Rot3.cpp.

Rot3 gtsam::Rot3::retractCayley ( const Vector omega) const
inline

Retraction from R^3 to Rot3 manifold using the Cayley transform.

Definition at line 358 of file Rot3.h.

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

Definition at line 243 of file Rot3.h.

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

Definition at line 254 of file Rot3.h.

static Rot3 gtsam::Rot3::Roll ( double  t)
inlinestatic

Definition at line 183 of file Rot3.h.

double gtsam::Rot3::roll ( OptionalJacobian< 1, 3 >  H = boost::none) 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

Definition at line 195 of file Rot3.cpp.

Point3 gtsam::Rot3::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 $

Definition at line 149 of file Rot3M.cpp.

Unit3 gtsam::Rot3::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

Definition at line 110 of file Rot3.cpp.

Vector3 gtsam::Rot3::rpy ( OptionalJacobian< 3, 3 >  H = boost::none) const

Use RQ to calculate roll-pitch-yaw angle representation

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

Definition at line 192 of file Rot3.cpp.

Rot3 gtsam::Rot3::Rx ( double  t)
static

Rotation around X axis as in http://en.wikipedia.org/wiki/Rotation_matrix, counterclockwise when looking from unchanging axis.

Definition at line 57 of file Rot3M.cpp.

Rot3 gtsam::Rot3::Ry ( double  t)
static

Rotation around Y axis as in http://en.wikipedia.org/wiki/Rotation_matrix, counterclockwise when looking from unchanging axis.

Definition at line 66 of file Rot3M.cpp.

Rot3 gtsam::Rot3::Rz ( double  t)
static

Rotation around Z axis as in http://en.wikipedia.org/wiki/Rotation_matrix, counterclockwise when looking from unchanging axis.

Definition at line 75 of file Rot3M.cpp.

Rot3 gtsam::Rot3::RzRyRx ( double  x,
double  y,
double  z,
OptionalJacobian< 3, 1 >  Hx = boost::none,
OptionalJacobian< 3, 1 >  Hy = boost::none,
OptionalJacobian< 3, 1 >  Hz = boost::none 
)
static

Rotations around Z, Y, then X axes as in http://en.wikipedia.org/wiki/Rotation_matrix, counterclockwise when looking from unchanging axis.

Definition at line 85 of file Rot3M.cpp.

static Rot3 gtsam::Rot3::RzRyRx ( const Vector xyz,
OptionalJacobian< 3, 3 >  H = boost::none 
)
inlinestatic

Rotations around Z, Y, then X axes as in http://en.wikipedia.org/wiki/Rotation_matrix, counterclockwise when looking from unchanging axis.

Definition at line 163 of file Rot3.h.

template<class ARCHIVE >
void gtsam::Rot3::serialize ( ARCHIVE &  ar,
const unsigned  int 
)
inlineprivate

Definition at line 543 of file Rot3.h.

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

Spherical Linear intERPolation between *this and other.

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

Definition at line 324 of file Rot3.cpp.

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

Compute the quaternion representation of this rotation.

Returns
The quaternion

Definition at line 233 of file Rot3M.cpp.

Matrix3 gtsam::Rot3::transpose ( ) const

Return 3*3 transpose (inverse) rotation matrix

Definition at line 144 of file Rot3M.cpp.

Point3 gtsam::Rot3::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 $

Definition at line 136 of file Rot3.cpp.

Unit3 gtsam::Rot3::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

Definition at line 120 of file Rot3.cpp.

Vector3 gtsam::Rot3::xyz ( OptionalJacobian< 3, 3 >  H = boost::none) const

Use RQ to calculate xyz angle representation

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

Definition at line 161 of file Rot3.cpp.

static Rot3 gtsam::Rot3::Yaw ( double  t)
inlinestatic

Positive yaw is to right (as in aircraft heading). See ypr.

Definition at line 177 of file Rot3.h.

double gtsam::Rot3::yaw ( OptionalJacobian< 1, 3 >  H = boost::none) 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

Definition at line 219 of file Rot3.cpp.

static Rot3 gtsam::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 
)
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).

Definition at line 199 of file Rot3.h.

Vector3 gtsam::Rot3::ypr ( OptionalJacobian< 3, 3 >  H = boost::none) const

Use RQ to calculate yaw-pitch-roll angle representation

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

Definition at line 184 of file Rot3.cpp.

Friends And Related Function Documentation

friend class boost::serialization::access
friend

Serialization function

Definition at line 541 of file Rot3.h.

GTSAM_EXPORT friend std::ostream& operator<< ( std::ostream &  os,
const Rot3 p 
)
friend

Output stream operator.

Member Data Documentation

SO3 gtsam::Rot3::rot_
private

Definition at line 67 of file Rot3.h.


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


gtsam
Author(s):
autogenerated on Sat May 8 2021 02:58:27