Vulcan
Aerospace Engineering Utilities Built on Janus
Loading...
Searching...
No Matches
vulcan::CoordinateFrame< Scalar > Struct Template Reference

#include <FramePrimitives.hpp>

Public Member Functions

 CoordinateFrame ()
 Default constructor - creates ECEF identity frame.
 CoordinateFrame (const Vec3< Scalar > &x, const Vec3< Scalar > &y, const Vec3< Scalar > &z, const Vec3< Scalar > &o)
 Construct from basis vectors and origin.
Vec3< Scalar > from_ecef (const Vec3< Scalar > &v) const
Vec3< Scalar > to_ecef (const Vec3< Scalar > &v) const
Vec3< Scalar > position_from_ecef (const Vec3< Scalar > &pos_ecef) const
Vec3< Scalar > position_to_ecef (const Vec3< Scalar > &pos_local) const
Mat3< Scalar > dcm () const
Mat3< Scalar > dcm_inverse () const
janus::Quaternion< Scalar > quaternion () const
bool is_valid (double tol=1e-9) const

Static Public Member Functions

static CoordinateFrame from_quaternion (const janus::Quaternion< Scalar > &q, const Vec3< Scalar > &o=Vec3< Scalar >::Zero())
static CoordinateFrame ecef ()
static CoordinateFrame eci (Scalar gmst)
static CoordinateFrame ned (Scalar lon, Scalar lat)
static CoordinateFrame enu (Scalar lon, Scalar lat)

Public Attributes

Vec3< Scalar > x_axis
 Unit X basis vector in ECEF.
Vec3< Scalar > y_axis
 Unit Y basis vector in ECEF.
Vec3< Scalar > z_axis
 Unit Z basis vector in ECEF.
Vec3< Scalar > origin
 Frame origin in ECEF [m].

Detailed Description

template<typename Scalar>
struct vulcan::CoordinateFrame< Scalar >

Coordinate frame defined by orthonormal basis vectors expressed in ECEF

This is the central abstraction for coordinate transformations in Vulcan. All frames are represented by three unit basis vectors (X, Y, Z axes) expressed in the ECEF (Earth-Centered Earth-Fixed) frame, plus an origin point. Transformations between frames are performed via dot products (projections) through ECEF as the hub.

This representation follows the TAOS specification's "Unit Vector Projection Method" which provides O(2N) transformations instead of O(N²) direct matrix pairs.

Example:

// Create an ECI frame at some time
double gmst = rotation.gmst(t);
// Transform a vector from ECEF to ECI
Vec3<double> v_ecef = {1000.0, 2000.0, 3000.0};
Vec3<double> v_eci = eci.from_ecef(v_ecef);
static CoordinateFrame eci(Scalar gmst)
Definition FramePrimitives.hpp:243
Vec3< Scalar > from_ecef(const Vec3< Scalar > &v) const
Definition FramePrimitives.hpp:75
Template Parameters
ScalarScalar type (double for numeric, janus::SymbolicScalar for symbolic)

Constructor & Destructor Documentation

◆ CoordinateFrame() [1/2]

template<typename Scalar>
vulcan::CoordinateFrame< Scalar >::CoordinateFrame ( )
inline

Default constructor - creates ECEF identity frame.

◆ CoordinateFrame() [2/2]

template<typename Scalar>
vulcan::CoordinateFrame< Scalar >::CoordinateFrame ( const Vec3< Scalar > & x,
const Vec3< Scalar > & y,
const Vec3< Scalar > & z,
const Vec3< Scalar > & o )
inline

Construct from basis vectors and origin.

Member Function Documentation

◆ dcm()

template<typename Scalar>
Mat3< Scalar > vulcan::CoordinateFrame< Scalar >::dcm ( ) const
inlinenodiscard

Compose DCM as column vectors [x_axis | y_axis | z_axis]

The DCM transforms vectors from this frame to ECEF: v_ecef = dcm() * v_local

Returns
3x3 Direction Cosine Matrix

◆ dcm_inverse()

template<typename Scalar>
Mat3< Scalar > vulcan::CoordinateFrame< Scalar >::dcm_inverse ( ) const
inlinenodiscard

Compose inverse DCM (ECEF to local)

The inverse DCM transforms vectors from ECEF to this frame: v_local = dcm_inverse() * v_ecef

For orthonormal frames, this is simply the transpose.

Returns
3x3 inverse (transpose) DCM

◆ ecef()

template<typename Scalar>
CoordinateFrame vulcan::CoordinateFrame< Scalar >::ecef ( )
inlinestatic

Create ECEF identity frame

X: Points to prime meridian at equator Y: Points to 90°E at equator Z: Points to North Pole

Returns
ECEF frame

◆ eci()

template<typename Scalar>
CoordinateFrame vulcan::CoordinateFrame< Scalar >::eci ( Scalar gmst)
inlinestatic

Create ECI (Earth-Centered Inertial) frame at given GMST

The ECI frame is rotated from ECEF about the Z-axis by the Greenwich Mean Sidereal Time (or Earth Rotation Angle).

At GMST=0, ECI aligns with ECEF (X points to vernal equinox, which coincides with Greenwich at epoch).

Parameters
gmstGreenwich Mean Sidereal Time [rad]
Returns
ECI frame expressed in ECEF

◆ enu()

template<typename Scalar>
CoordinateFrame vulcan::CoordinateFrame< Scalar >::enu ( Scalar lon,
Scalar lat )
inlinestatic

Create ENU (East-North-Up) frame at given geodetic position

X: Points East (tangent to parallel) Y: Points North (tangent to meridian) Z: Points Up (ellipsoid normal)

Common in surveying and some navigation applications.

Parameters
lonLongitude [rad]
latGeodetic latitude [rad]
Returns
ENU frame expressed in ECEF

◆ from_ecef()

template<typename Scalar>
Vec3< Scalar > vulcan::CoordinateFrame< Scalar >::from_ecef ( const Vec3< Scalar > & v) const
inlinenodiscard

Project vector FROM ECEF TO this frame (rotation only)

Uses dot product projections onto basis vectors. This is equivalent to multiplying by the DCM transpose.

Parameters
vVector expressed in ECEF
Returns
Vector expressed in this frame

◆ from_quaternion()

template<typename Scalar>
CoordinateFrame vulcan::CoordinateFrame< Scalar >::from_quaternion ( const janus::Quaternion< Scalar > & q,
const Vec3< Scalar > & o = Vec3<Scalar>::Zero() )
inlinestatic

Create frame from quaternion and origin

The quaternion should represent the rotation from ECEF to the target frame (i.e., how to transform ECEF vectors to local coords).

Parameters
qQuaternion (ECEF to local rotation)
oOrigin in ECEF [m]
Returns
CoordinateFrame

◆ is_valid()

template<typename Scalar>
bool vulcan::CoordinateFrame< Scalar >::is_valid ( double tol = 1e-9) const
inlinenodiscard

Check if frame is orthonormal within tolerance

Verifies:

  • All basis vectors are unit length
  • All basis vectors are mutually orthogonal
Parameters
tolTolerance for numerical checks
Returns
True if frame is valid

◆ ned()

template<typename Scalar>
CoordinateFrame vulcan::CoordinateFrame< Scalar >::ned ( Scalar lon,
Scalar lat )
inlinestatic

Create NED (North-East-Down) frame at given geodetic position

X: Points North (tangent to meridian) Y: Points East (tangent to parallel) Z: Points Down (opposite to ellipsoid normal)

This is the standard aerospace local horizon frame.

Parameters
lonLongitude [rad]
latGeodetic latitude [rad]
Returns
NED frame expressed in ECEF

◆ position_from_ecef()

template<typename Scalar>
Vec3< Scalar > vulcan::CoordinateFrame< Scalar >::position_from_ecef ( const Vec3< Scalar > & pos_ecef) const
inlinenodiscard

Transform position FROM ECEF TO this frame (includes origin offset)

Parameters
pos_ecefPosition in ECEF [m]
Returns
Position in this frame [m]

◆ position_to_ecef()

template<typename Scalar>
Vec3< Scalar > vulcan::CoordinateFrame< Scalar >::position_to_ecef ( const Vec3< Scalar > & pos_local) const
inlinenodiscard

Transform position FROM this frame TO ECEF (includes origin offset)

Parameters
pos_localPosition in this frame [m]
Returns
Position in ECEF [m]

◆ quaternion()

template<typename Scalar>
janus::Quaternion< Scalar > vulcan::CoordinateFrame< Scalar >::quaternion ( ) const
inlinenodiscard

Get frame orientation as quaternion (rotation from ECEF to this frame)

The quaternion represents the rotation that transforms vectors from ECEF coordinates to this frame's coordinates.

Returns
Quaternion representing frame orientation

◆ to_ecef()

template<typename Scalar>
Vec3< Scalar > vulcan::CoordinateFrame< Scalar >::to_ecef ( const Vec3< Scalar > & v) const
inlinenodiscard

Project vector FROM this frame TO ECEF (rotation only)

Reconstructs ECEF vector from local components. This is equivalent to multiplying by the DCM.

Parameters
vVector expressed in this frame
Returns
Vector expressed in ECEF

Member Data Documentation

◆ origin

template<typename Scalar>
Vec3<Scalar> vulcan::CoordinateFrame< Scalar >::origin

Frame origin in ECEF [m].

◆ x_axis

template<typename Scalar>
Vec3<Scalar> vulcan::CoordinateFrame< Scalar >::x_axis

Unit X basis vector in ECEF.

◆ y_axis

template<typename Scalar>
Vec3<Scalar> vulcan::CoordinateFrame< Scalar >::y_axis

Unit Y basis vector in ECEF.

◆ z_axis

template<typename Scalar>
Vec3<Scalar> vulcan::CoordinateFrame< Scalar >::z_axis

Unit Z basis vector in ECEF.


The documentation for this struct was generated from the following file: