math::SO3#

rb::math::SO3 provides rotation-matrix helpers for 3D orientation work. Use it when you need rotation construction, conversion, exponential or logarithmic maps, or projection back onto SO(3).

Header

Header

#include <rby1-sdk/math/so3.h>

Declaration

Namespace

rb::math

Kind

class

Primary role

Provide static helpers for 3D rotation operations.

Member Types

Type

Purpose

Notes

MatrixType

Matrix representation used by the rotation helpers.

Returned by the construction methods on this page.

Public Member Functions

Method group

Purpose

Notes

Identity(), Inverse(...), Projection(...)

Create or sanitize rotation matrices.

Use Projection(...) after noisy numeric operations.

RotX/Y/Z(...) and FromRPY(...) / ToRPY(...)

Convert to or from standard axis-angle or roll-pitch-yaw forms.

Good entry point for user-facing rotations.

FromQuaternion(...) / ToQuaternion(...) and Euler helpers

Convert between matrix and alternate orientation parameterizations.

Covers both quaternion and Euler-angle conventions.

Exp(...), Log(...), Hat(...), Vec(...)

Work in the Lie algebra and tangent space.

Useful in estimators and geometric controllers.

Average(...) and axis getters

Average multiple rotations or inspect basis axes.

Convenient analysis utilities.

Detailed Reference

class SO3#

Public Types

using MatrixType = Eigen::Matrix3d#

Public Static Functions

template<typename Container, typename = std::enable_if_t<std::is_same_v<typename Container::value_type, MatrixType>>>
static inline std::optional<MatrixType> Average(const Container &matrices, double eps, int max_iter = -1)#
static MatrixType Exp(so3v::MatrixType w, double angle = 1.0)#
static MatrixType FromEulerAngle(const Eigen::Vector3d &angles, EulerAngleType type)#
static MatrixType FromQuaternion(const Eigen::Quaterniond &q)#
static MatrixType FromRPY(const Eigen::Vector3d &angles)#

Calculate rotation from roll, pitch and yqw angles

Parameters:

angles – [0] roll [1] pitch [2] yaw

Returns:

static Eigen::Vector3d GetX(const MatrixType &R)#
static Eigen::Vector3d GetY(const MatrixType &R)#
static Eigen::Vector3d GetZ(const MatrixType &R)#
static so3::MatrixType Hat(const so3v::MatrixType &w)#
static MatrixType Identity()#
static MatrixType Inverse(const MatrixType &R)#
static so3v::MatrixType Log(const MatrixType &R)#
static MatrixType Projection(const MatrixType &m)#
static MatrixType RotX(double angle)#
static MatrixType RotY(double angle)#
static MatrixType RotZ(double angle)#
static Eigen::Vector3d ToEulerAngle(const MatrixType &R, EulerAngleType type)#
static Eigen::Quaterniond ToQuaternion(const MatrixType &R)#
static Eigen::Vector3d ToRPY(const MatrixType &R)#
Parameters:

R

Returns:

[0] roll [1] pitch [2] yaw

static so3v::MatrixType Vec(const so3::MatrixType &r)#

Related Types

Examples

  • so3.cpp is the direct example for this page.