The refx
Library
refx
is a modern C++ header-only library for robust robotics and navigation applications. It leverages the C++ type system to enforce coordinate frame correctness at compile-time, preventing an entire class of common runtime errors by making invalid geometric operations a compilation failure.
The library's core philosophy is the separation of a frame's name, its axis structure, and its semantic classification. It provides a suite of frame-aware geometric types, a powerful transformation API, and a set of standard physical models for high-fidelity geodetic calculations.
Key Features
- Compile-Time Safety: Enforces frame-aware mathematics for vectors, rotations, and transformations. Operations between incompatible frames are caught by the compiler.
- Expressive Geometry Types: Provides strongly-typed classes like
Vector3D<Frame>
,Coordinate3D<Frame>
,Rotation<To, From>
, andTransformation<To, From>
. - Comprehensive Frame System: Includes a rich set of predefined geodetic, local-tangent, body, and sensor frames (
lla
,ned
,frd
,imu
, etc.) and is fully extensible with user-defined frames. - High-Fidelity Models: Ships with standard geodetic models, including WGS-84 and GRS-80 reference ellipsoids and gravity models, for accurate real-world calculations.
- Powerful Transformation API: Offers a unified API with
frame_cast
for simple co-origin conversions andframe_transform
for complex, model-based geodetic projections.
Requirements
Developing with refx requires only a C++17 compatible compiler. Running library unit-tests requires Google Test as dependency (downloaded automatically by CMake).
Safety Through Types
In complex navigation systems, ensuring the semantic correctness of coordinate frames is critical. Implicit conventions often lead to runtime errors when, for example, a vector in a body frame is incorrectly added to a vector in a world frame.
refx
prevents this by encoding the frame into the type itself. The following code will not compile, saving hours of potential debugging:
#include <refx/geometry.h>
int main() {
// A velocity vector in the world (NED) frame
refx::Vector3D<refx::ned> velocity_world(10.0, 5.0, 0.0);
// A velocity vector in the vehicle's body (FRD) frame
refx::Vector3D<refx::frd> velocity_body(1.0, 0.0, 0.0);
// COMPILE-TIME ERROR: static assertion failed due to different FrameTags.
auto invalid_sum = velocity_world + velocity_body;
return 0;
}