math::SE3#

rb::math::SE3 provides 3D rigid transform helpers. It is the natural companion to SO3 when controllers or planners need poses, twists, or adjoint operators between reference frames.

Header

Header

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

Declaration

Namespace

rb::math

Kind

class

Primary role

Provide static helpers for 3D rigid transforms and adjoint operations.

Member Types

Type

Purpose

Notes

MatrixType

Matrix representation used by the transform helpers.

Returned by the construction methods on this page.

Public Member Functions

Method group

Purpose

Notes

Identity(), T(...), Inverse(...)

Create or invert rigid transforms.

T(...) builds transforms from position and rotation data.

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

Move between transform matrices and twist-space representations.

Common in model-based control and estimation.

Ad(...), InvAd(...), ad(...), adTranspose(...)

Apply adjoint and Lie-bracket operators.

Useful for wrench and twist transforms.

GetPosition(...), GetRotation(...), Multiply(...)

Extract components or apply a transform to a point.

Good for task-space utility code.

Average(...)

Average a set of rigid transforms.

Useful for pose filtering and alignment.

Detailed Reference

class SE3#

Public Types

using MatrixType = Eigen::Matrix4d#

Public Static Functions

static Eigen::Matrix<double, 6, 6> Ad(const MatrixType &T)#
static se3v::MatrixType Ad(const MatrixType &T, const se3v::MatrixType &S)#
static Eigen::Matrix<double, 6, 6> ad(const se3v::MatrixType &S)#
static se3v::MatrixType ad(const se3v::MatrixType &S1, const se3v::MatrixType &S2)#
static Eigen::Matrix<double, 6, 6> adTranspose(const se3v::MatrixType &S)#
static se3v::MatrixType adTranspose(const se3v::MatrixType &S1, const se3v::MatrixType &S2)#
template<typename Container, typename = std::enable_if_t<std::is_same_v<typename Container::value_type, MatrixType>>>
static std::optional<MatrixType> Average(const Container &matrices, double eps, int max_iter = -1)#
static MatrixType Exp(const se3v::MatrixType &S, double angle = 1.)#
static MatrixType Exp(so3v::MatrixType w, Eigen::Vector3d v, double angle = 1.)#
static Eigen::Vector3d GetPosition(const MatrixType &T)#
static SO3::MatrixType GetRotation(const MatrixType &T)#
static se3::MatrixType Hat(const se3v::MatrixType &v)#
static MatrixType Identity()#
static Eigen::Matrix<double, 6, 6> InvAd(const MatrixType &T)#
static se3v::MatrixType InvAd(const MatrixType &T, const se3v::MatrixType &S)#
static MatrixType Inverse(const MatrixType &T)#
static se3v::MatrixType Log(const MatrixType &T)#
static Eigen::Vector3d Multiply(const MatrixType &T, const Eigen::Vector3d &p)#
static MatrixType T(const Eigen::Vector3d &p)#
static MatrixType T(const SO3::MatrixType &R, const Eigen::Vector3d &p = Eigen::Vector3d::Zero())#
static se3v::MatrixType Vec(const se3::MatrixType &s)#

Related Types

Examples

  • dynamics/load_urdf.cpp and optimal_control.cpp are good places to see SE3 in context.