This guide covers the unified rotations library in Vulcan, providing comprehensive utilities for 3D rotation representations including all 12 Euler angle sequences, quaternions, DCMs, and axis-angle conversions.
Quick Start
double yaw = 0.5, pitch = 0.3, roll = 0.1;
Definition Aerodynamics.hpp:11
Mat3< Scalar > dcm_from_euler(Scalar e1, Scalar e2, Scalar e3, EulerSequence seq)
Definition EulerSequences.hpp:143
Vec3< Scalar > euler_from_dcm(const Mat3< Scalar > &R, EulerSequence seq)
Definition EulerSequences.hpp:520
janus::Quaternion< Scalar > quaternion_from_euler(Scalar e1, Scalar e2, Scalar e3, EulerSequence seq)
Definition EulerSequences.hpp:170
@ ZYX
Yaw-Pitch-Roll (aerospace standard).
Definition EulerSequences.hpp:39
Euler Angle Sequences
Vulcan supports all 12 Euler angle sequences, organized into two categories:
Tait-Bryan Sequences (3 distinct axes)
| Sequence | Convention | Common Use |
| ZYX | Yaw-Pitch-Roll | Aerospace (default) |
| XYZ | Roll-Pitch-Yaw | Robotics |
| YXZ | | Computer graphics |
| ZXY | | |
| XZY | | |
| YZX | | |
Proper Euler Sequences (symmetric axes)
| Sequence | Convention | Common Use |
| ZXZ | Precession-Nutation-Spin | Classical mechanics, orbital |
| ZYZ | | Robotics (wrist) |
| XYX | | |
| XZX | | |
| YXY | | |
| YZY | | |
Creating Rotations from Euler Angles
@ ZXZ
Classical mechanics (precession-nutation-spin).
Definition EulerSequences.hpp:46
@ XYZ
Roll-Pitch-Yaw (robotics convention).
Definition EulerSequences.hpp:34
Extracting Euler Angles
Vec3< Scalar > euler_from_quaternion(const janus::Quaternion< Scalar > &q, EulerSequence seq)
Definition EulerSequences.hpp:558
Gimbal Lock Handling
All Euler angle extractions handle gimbal lock robustly using janus::where for symbolic compatibility:
- Tait-Bryan: At ±90° pitch, roll is set to 0
- Proper Euler: At 0° or 180° nutation, spin is set to 0
double pitch = M_PI / 2.0;
DCM Utilities
Skew-Symmetric Matrix
Vec3<double> omega;
omega << 0.1, 0.2, 0.3;
Mat3<double> S =
skew(omega);
Vec3<double> omega_back =
unskew(S);
Mat3< Scalar > skew(const Vec3< Scalar > &v)
Definition DCMUtils.hpp:32
Vec3< Scalar > unskew(const Mat3< Scalar > &S)
Definition DCMUtils.hpp:53
DCM Composition
Mat3< Scalar > relative_dcm(const Mat3< Scalar > &R_A, const Mat3< Scalar > &R_B)
Definition DCMUtils.hpp:93
Mat3< Scalar > compose_dcm(const Mat3< Scalar > &R1, const Mat3< Scalar > &R2)
Definition DCMUtils.hpp:75
Small-Angle Approximation
For linearized analysis and estimation:
Vec3<double> theta;
theta << 0.01, -0.02, 0.015;
Vec3< Scalar > small_angle_from_dcm(const Mat3< Scalar > &R)
Definition DCMUtils.hpp:128
Mat3< Scalar > dcm_from_small_angle(const Vec3< Scalar > &theta)
Definition DCMUtils.hpp:112
DCM Validation
}
auto is_valid_dcm(const Eigen::MatrixBase< Derived > &R, double tol=1e-9)
Definition DCMUtils.hpp:152
Axis-Angle and Rotation Vectors
Creating Rotations
Vec3<double> axis;
axis << 0.0, 0.0, 1.0;
double angle = M_PI / 4.0;
Vec3<double> rot_vec;
rot_vec << 0.3, -0.2, 0.5;
janus::Quaternion< Scalar > quaternion_from_rotation_vector(const Vec3< Scalar > &rot_vec)
Definition AxisAngle.hpp:41
Mat3< Scalar > dcm_from_rotation_vector(const Vec3< Scalar > &rot_vec)
Definition AxisAngle.hpp:88
janus::Quaternion< Scalar > quaternion_from_axis_angle(const Vec3< Scalar > &axis, Scalar angle)
Definition AxisAngle.hpp:29
Mat3< Scalar > dcm_from_axis_angle(const Vec3< Scalar > &axis, Scalar angle)
Definition AxisAngle.hpp:60
Extracting Axis-Angle
std::pair< Vec3< Scalar >, Scalar > axis_angle_from_dcm(const Mat3< Scalar > &R)
Definition AxisAngle.hpp:165
Vec3< Scalar > rotation_vector_from_quaternion(const janus::Quaternion< Scalar > &q)
Definition AxisAngle.hpp:143
Vec3< Scalar > rotation_vector_from_dcm(const Mat3< Scalar > &R)
Definition AxisAngle.hpp:213
std::pair< Vec3< Scalar >, Scalar > axis_angle_from_quaternion(const janus::Quaternion< Scalar > &q)
Definition AxisAngle.hpp:112
Rotation Kinematics
Quaternion Rate ↔ Angular Velocity
Vec3<double> omega_body;
omega_body << 0.1, 0.05, 0.02;
Vec3< Scalar > omega_from_quaternion_rate(const janus::Quaternion< Scalar > &q, const janus::Quaternion< Scalar > &q_dot)
Definition RotationKinematics.hpp:30
janus::Quaternion< Scalar > quaternion_rate_from_omega(const janus::Quaternion< Scalar > &q, const Vec3< Scalar > &omega_body)
Definition RotationKinematics.hpp:56
DCM Rate ↔ Angular Velocity
Mat3< Scalar > dcm_rate_from_omega(const Mat3< Scalar > &R, const Vec3< Scalar > &omega_body)
Definition RotationKinematics.hpp:100
Vec3< Scalar > omega_from_dcm_rate(const Mat3< Scalar > &R, const Mat3< Scalar > &R_dot)
Definition RotationKinematics.hpp:84
Rotation Composition and Error
janus::Quaternion< Scalar > compose_rotations(const janus::Quaternion< Scalar > &q1, const janus::Quaternion< Scalar > &q2)
Definition RotationKinematics.hpp:121
janus::Quaternion< Scalar > relative_rotation(const janus::Quaternion< Scalar > &q_from, const janus::Quaternion< Scalar > &q_to)
Definition RotationKinematics.hpp:138
Vec3< Scalar > rotation_error(const janus::Quaternion< Scalar > &q_actual, const janus::Quaternion< Scalar > &q_desired)
Definition RotationKinematics.hpp:155
Interpolation
Slerp (Spherical Linear Interpolation)
auto q_interp =
slerp(q0, q1, t);
for (double t = 0.0; t <= 1.0; t += 0.1) {
auto q =
slerp(q_start, q_end, t);
}
janus::Quaternion< Scalar > slerp(const janus::Quaternion< Scalar > &q0, const janus::Quaternion< Scalar > &q1, Scalar t)
Definition Interpolation.hpp:27
Squad (Spherical Quadrangle Interpolation)
For C1-continuous rotation curves through waypoints:
auto q_interp =
squad(q1, q2, s1, s2, t);
janus::Quaternion< Scalar > squad_control_point(const janus::Quaternion< Scalar > &q_prev, const janus::Quaternion< Scalar > &q_curr, const janus::Quaternion< Scalar > &q_next)
Definition Interpolation.hpp:117
janus::Quaternion< Scalar > squad(const janus::Quaternion< Scalar > &q0, const janus::Quaternion< Scalar > &q1, const janus::Quaternion< Scalar > &s0, const janus::Quaternion< Scalar > &s1, Scalar t)
Definition Interpolation.hpp:151
Symbolic Computation
All functions are templated and work with janus::SymbolicScalar for optimization:
using Scalar = janus::SymbolicScalar;
Scalar yaw = janus::sym("yaw");
Scalar pitch = janus::sym("pitch");
Scalar roll = janus::sym("roll");
std::cout << R(0, 0) << std::endl;
janus::Function f("attitude_dcm", {yaw, pitch, roll},
{R(0,0), R(1,0), R(2,0)});
Integration with CoordinateFrame
The rotations library integrates with Vulcan's coordinate frame system:
#include <vulcan/coordinates/BodyFrames.hpp>
Vec3< Scalar > euler_from_body(const CoordinateFrame< Scalar > &body, const CoordinateFrame< Scalar > &ned)
Definition FrameVehicle.hpp:123
CoordinateFrame< Scalar > body_from_euler(const CoordinateFrame< Scalar > &ned, Scalar yaw, Scalar pitch, Scalar roll)
Definition FrameVehicle.hpp:99
Graph Visualization
Export computational graphs as interactive HTML for debugging and documentation:
using Scalar = janus::SymbolicScalar;
Scalar yaw = janus::sym("yaw");
Scalar pitch = janus::sym("pitch");
Scalar roll = janus::sym("roll");
janus::export_graph_html(R(0, 0), "graph_dcm_r00", "DCM_R00_ZYX");
The generated HTML files are self-contained and can be:
- Opened in any web browser
- Shared for documentation
- Used to visualize complex symbolic expressions
API Reference
EulerSequences.hpp
| Function | Description |
| dcm_from_euler(e1, e2, e3, seq) | Create DCM from Euler angles |
| quaternion_from_euler(e1, e2, e3, seq) | Create quaternion from Euler angles |
| euler_from_dcm(R, seq) | Extract Euler angles from DCM |
| euler_from_quaternion(q, seq) | Extract Euler angles from quaternion |
| euler_axes(seq) | Get axis indices [0=X, 1=Y, 2=Z] |
| is_proper_euler(seq) | Check if sequence is proper Euler |
| euler_sequence_name(seq) | Get sequence name as string |
DCMUtils.hpp
| Function | Description |
| skew(v) | Create skew-symmetric matrix from vector |
| unskew(S) | Extract vector from skew-symmetric matrix |
| compose_dcm(R1, R2) | Compose DCMs: R2 * R1 |
| relative_dcm(R_A, R_B) | Relative DCM from A to B |
| dcm_from_small_angle(theta) | First-order DCM approximation |
| small_angle_from_dcm(R) | Extract small angles from near-identity DCM |
| is_valid_dcm(R) | Check if matrix is valid rotation |
| dcm_principal_axis(theta, axis) | DCM for principal axis rotation |
AxisAngle.hpp
| Function | Description |
| quaternion_from_axis_angle(axis, angle) | Quaternion from axis-angle |
| quaternion_from_rotation_vector(rot_vec) | Quaternion from rotation vector |
| dcm_from_axis_angle(axis, angle) | DCM via Rodrigues' formula |
| dcm_from_rotation_vector(rot_vec) | DCM from rotation vector |
| axis_angle_from_quaternion(q) | Extract axis and angle from quaternion |
| axis_angle_from_dcm(R) | Extract axis and angle from DCM |
| rotation_vector_from_quaternion(q) | Rotation vector from quaternion |
| rotation_vector_from_dcm(R) | Rotation vector from DCM |
RotationKinematics.hpp
| Function | Description |
| omega_from_quaternion_rate(q, q_dot) | Angular velocity from quaternion rate |
| quaternion_rate_from_omega(q, omega) | Quaternion rate from angular velocity |
| omega_from_dcm_rate(R, R_dot) | Angular velocity from DCM rate |
| dcm_rate_from_omega(R, omega) | DCM rate from angular velocity |
| compose_rotations(q1, q2) | Compose quaternion rotations |
| relative_rotation(q_from, q_to) | Relative rotation quaternion |
| rotation_error(q_actual, q_desired) | Rotation error as rotation vector |
Interpolation.hpp
| Function | Description |
| slerp(q0, q1, t) | Spherical linear interpolation |
| quat_exp(v) | Quaternion exponential |
| quat_log(q) | Quaternion logarithm |
| squad_control_point(q_prev, q_curr, q_next) | Squad control point |
| squad(q0, q1, s0, s1, t) | Squad interpolation |
Example: Complete Demo
See examples/rotations/rotations_demo.cpp for a comprehensive demonstration of all features.
# Build and run the demo
./scripts/build.sh
./build/examples/rotations_demo