|
| 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.
|
|
|
|
void | print (const std::string &s="R") const |
| print
|
|
bool | equals (const Rot3 &p, double tol=1e-9) const |
| equals with an tolerance
|
|
|
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 \)
|
|
|
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
|
|
|
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.
|
|
| BOOST_STATIC_ASSERT_MSG (N !=Eigen::Dynamic, "LieGroup not yet specialized for dynamically sized types.") |
|
const Rot3 & | derived () 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
|
|
|
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.
|
|
enum | |
|
typedef OptionalJacobian< N, N > | ChartJacobian |
|
typedef Eigen::Matrix< double, N, N > | Jacobian |
|
typedef Eigen::Matrix< double, N, 1 > | TangentVector |
|
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).