Classes | Static Public Attributes | Private Attributes | List of all members
gtsam::Gal3 Class Reference

#include <Gal3.h>

Inheritance diagram for gtsam::Gal3:
Inheritance graph
[legend]

Classes

struct  ChartAtOrigin
 Chart at origin, uses Expmap/Logmap for Retract/Local. More...
 

Public Member Functions

Component Access
const Rot3rotation (OptionalJacobian< 3, 10 > H={}) const
 Access rotation component (Rot3) More...
 
const Point3translation (OptionalJacobian< 3, 10 > H={}) const
 Access translation component (Point3) More...
 
const Velocity3velocity (OptionalJacobian< 3, 10 > H={}) const
 Access velocity component (Vector3) More...
 
const double & time (OptionalJacobian< 1, 10 > H={}) const
 Access time component (double) More...
 
const Rot3attitude (OptionalJacobian< 3, 10 > H={}) const
 
const Point3position (OptionalJacobian< 3, 10 > H={}) const
 
Derived quantities
Matrix3 R () const
 Return rotation matrix (Matrix3) More...
 
Vector3 r () const
 Return position as Vector3. More...
 
const Vector3v () const
 Return velocity as Vector3. More...
 
const double & t () const
 Return time scalar. More...
 
Matrix5 matrix () const
 Return 5x5 homogeneous matrix representation. More...
 
Group Action
Event act (const Event &e, OptionalJacobian< 4, 10 > Hself={}, OptionalJacobian< 4, 4 > He={}) const
 
- Public Member Functions inherited from gtsam::LieGroup< Gal3, 10 >
Gal3 between (const Gal3 &g) const
 
Gal3 between (const Gal3 &g, ChartJacobian H1, ChartJacobian H2={}) const
 
SOn between (const SOn &g, DynamicJacobian H1, DynamicJacobian H2) const
 
GTSAM_EXPORT SOn between (const SOn &g, DynamicJacobian H1, DynamicJacobian H2) const
 
Gal3 compose (const Gal3 &g) const
 
Gal3 compose (const Gal3 &g, ChartJacobian H1, ChartJacobian H2={}) const
 
SOn compose (const SOn &g, DynamicJacobian H1, DynamicJacobian H2) const
 
GTSAM_EXPORT SOn compose (const SOn &g, DynamicJacobian H1, DynamicJacobian H2) const
 
const Gal3derived () const
 
Gal3 expmap (const TangentVector &v) const
 
Gal3 expmap (const TangentVector &v, ChartJacobian H1, ChartJacobian H2={}) const
 expmap with optional derivatives More...
 
Gal3 inverse (ChartJacobian H) const
 
TangentVector localCoordinates (const Gal3 &g) const
 localCoordinates as required by manifold concept: finds tangent vector between *this and g More...
 
TangentVector localCoordinates (const Gal3 &g, ChartJacobian H1, ChartJacobian H2={}) const
 localCoordinates with optional derivatives More...
 
TangentVector logmap (const Gal3 &g) const
 
TangentVector logmap (const Gal3 &g, ChartJacobian H1, ChartJacobian H2={}) const
 logmap with optional derivatives More...
 
Gal3 retract (const TangentVector &v) const
 retract as required by manifold concept: applies v at *this More...
 
Gal3 retract (const TangentVector &v, ChartJacobian H1, ChartJacobian H2={}) const
 retract with optional derivatives More...
 

Static Public Attributes

static constexpr size_t dimension = 10
 The dimension of the tangent space. More...
 
- Static Public Attributes inherited from gtsam::LieGroup< Gal3, 10 >
constexpr static auto dimension
 

Private Attributes

Rot3 R_
 Rotation world R body. More...
 
Point3 r_
 Position in world frame, n_r_b. More...
 
double t_
 Time component. More...
 
Velocity3 v_
 Velocity in world frame, n_v_b. More...
 

Constructors

 Gal3 ()
 Default constructor: Identity element. More...
 
 Gal3 (const Rot3 &R, const Point3 &r, const Velocity3 &v, double t)
 Construct from attitude, position, velocity, time. More...
 
 Gal3 (const Matrix5 &M)
 Construct from a 5x5 matrix representation. More...
 
static Gal3 Create (const Rot3 &R, const Point3 &r, const Velocity3 &v, double t, OptionalJacobian< 10, 3 > H1={}, OptionalJacobian< 10, 3 > H2={}, OptionalJacobian< 10, 3 > H3={}, OptionalJacobian< 10, 1 > H4={})
 Named constructor from components with derivatives. More...
 
static Gal3 FromPoseVelocityTime (const Pose3 &pose, const Velocity3 &v, double t, OptionalJacobian< 10, 6 > H1={}, OptionalJacobian< 10, 3 > H2={}, OptionalJacobian< 10, 1 > H3={})
 Named constructor from Pose3, velocity, and time with derivatives. More...
 

Testable

void print (const std::string &s="") const
 Print with optional string prefix. More...
 
bool equals (const Gal3 &other, double tol=1e-9) const
 Check equality within tolerance. More...
 
GTSAM_EXPORT friend std::ostream & operator<< (std::ostream &os, const Gal3 &state)
 Output stream operator. More...
 

Group

Gal3 inverse () const
 Return the inverse of this element. More...
 
Gal3 operator* (const Gal3 &other) const
 Group composition operator. More...
 
static Gal3 Identity ()
 Return the identity element. More...
 

Lie Group Static Functions

Matrix10 AdjointMap () const
 Calculate Adjoint map Ad_g. More...
 
Vector10 Adjoint (const Vector10 &xi_base, OptionalJacobian< 10, 10 > H_g={}, OptionalJacobian< 10, 10 > H_xi={}) const
 Apply this element's AdjointMap Ad_g to a tangent vector xi_base at identity. More...
 
static Gal3 Expmap (const Vector10 &xi, OptionalJacobian< 10, 10 > Hxi={})
 Exponential map at identity: tangent vector xi -> manifold element g. More...
 
static Vector10 Logmap (const Gal3 &g, OptionalJacobian< 10, 10 > Hg={})
 Logarithmic map at identity: manifold element g -> tangent vector xi. More...
 
static Vector10 adjoint (const Vector10 &xi, const Vector10 &y, OptionalJacobian< 10, 10 > Hxi={}, OptionalJacobian< 10, 10 > Hy={})
 The adjoint action ad(xi, y) = adjointMap(xi) * y More...
 
static Matrix10 adjointMap (const Vector10 &xi)
 Compute the adjoint map ad(xi) associated with tangent vector xi. More...
 
static Matrix10 ExpmapDerivative (const Vector10 &xi)
 Derivative of Expmap(xi) w.r.t. xi evaluated at xi. More...
 
static Matrix10 LogmapDerivative (const Gal3 &g)
 Derivative of Logmap(g) w.r.t. g. More...
 
static Matrix5 Hat (const Vector10 &xi)
 Hat operator: maps tangent vector xi to Lie algebra matrix. More...
 
static Vector10 Vee (const Matrix5 &X)
 Vee operator: maps Lie algebra matrix to tangent vector xi. More...
 

Additional Inherited Members

- Public Types inherited from gtsam::LieGroup< Gal3, 10 >
typedef OptionalJacobian< N, NChartJacobian
 
typedef Eigen::Matrix< double, N, NJacobian
 
typedef Eigen::Matrix< double, N, 1 > TangentVector
 
- Static Public Member Functions inherited from gtsam::LieGroup< Gal3, 10 >
static TangentVector LocalCoordinates (const Gal3 &g)
 LocalCoordinates at origin: possible in Lie group because it has an identity. More...
 
static TangentVector LocalCoordinates (const Gal3 &g, ChartJacobian H)
 LocalCoordinates at origin with optional derivative. More...
 
static Gal3 Retract (const TangentVector &v)
 Retract at origin: possible in Lie group because it has an identity. More...
 
static Gal3 Retract (const TangentVector &v, ChartJacobian H)
 Retract at origin with optional derivative. More...
 

Detailed Description

Represents an element of the 3D Galilean group SGal(3). Internal state: rotation, translation, velocity, time.

Definition at line 45 of file Gal3.h.

Constructor & Destructor Documentation

◆ Gal3() [1/3]

gtsam::Gal3::Gal3 ( )
inline

Default constructor: Identity element.

Definition at line 61 of file Gal3.h.

◆ Gal3() [2/3]

gtsam::Gal3::Gal3 ( const Rot3 R,
const Point3 r,
const Velocity3 v,
double  t 
)
inline

Construct from attitude, position, velocity, time.

Definition at line 64 of file Gal3.h.

◆ Gal3() [3/3]

gtsam::Gal3::Gal3 ( const Matrix5 M)
explicit

Construct from a 5x5 matrix representation.

Definition at line 114 of file Gal3.cpp.

Member Function Documentation

◆ act()

Event gtsam::Gal3::act ( const Event e,
OptionalJacobian< 4, 10 >  Hself = {},
OptionalJacobian< 4, 4 >  He = {} 
) const

Apply Galilean transform to a spacetime Event

Parameters
eInput event (location, time)
HselfOptional Jacobian wrt this Gal3 element's tangent space
HeOptional Jacobian wrt the input event's tangent space
Returns
Transformed event

Definition at line 463 of file Gal3.cpp.

◆ adjoint()

Vector10 gtsam::Gal3::adjoint ( const Vector10 xi,
const Vector10 y,
OptionalJacobian< 10, 10 >  Hxi = {},
OptionalJacobian< 10, 10 >  Hy = {} 
)
static

The adjoint action ad(xi, y) = adjointMap(xi) * y

Definition at line 382 of file Gal3.cpp.

◆ Adjoint()

Vector10 gtsam::Gal3::Adjoint ( const Vector10 xi_base,
OptionalJacobian< 10, 10 >  H_g = {},
OptionalJacobian< 10, 10 >  H_xi = {} 
) const

Apply this element's AdjointMap Ad_g to a tangent vector xi_base at identity.

Definition at line 336 of file Gal3.cpp.

◆ AdjointMap()

Matrix10 gtsam::Gal3::AdjointMap ( ) const

Calculate Adjoint map Ad_g.

Definition at line 312 of file Gal3.cpp.

◆ adjointMap()

Matrix10 gtsam::Gal3::adjointMap ( const Vector10 xi)
static

Compute the adjoint map ad(xi) associated with tangent vector xi.

Definition at line 358 of file Gal3.cpp.

◆ attitude()

const Rot3& gtsam::Gal3::attitude ( OptionalJacobian< 3, 10 >  H = {}) const
inline

Definition at line 100 of file Gal3.h.

◆ Create()

Gal3 gtsam::Gal3::Create ( const Rot3 R,
const Point3 r,
const Velocity3 v,
double  t,
OptionalJacobian< 10, 3 >  H1 = {},
OptionalJacobian< 10, 3 >  H2 = {},
OptionalJacobian< 10, 3 >  H3 = {},
OptionalJacobian< 10, 1 >  H4 = {} 
)
static

Named constructor from components with derivatives.

Definition at line 63 of file Gal3.cpp.

◆ equals()

bool gtsam::Gal3::equals ( const Gal3 other,
double  tol = 1e-9 
) const

Check equality within tolerance.

Definition at line 200 of file Gal3.cpp.

◆ Expmap()

gtsam::Gal3 gtsam::Gal3::Expmap ( const Vector10 xi,
OptionalJacobian< 10, 10 >  Hxi = {} 
)
static

Exponential map at identity: tangent vector xi -> manifold element g.

Definition at line 238 of file Gal3.cpp.

◆ ExpmapDerivative()

Matrix10 gtsam::Gal3::ExpmapDerivative ( const Vector10 xi)
static

Derivative of Expmap(xi) w.r.t. xi evaluated at xi.

Definition at line 392 of file Gal3.cpp.

◆ FromPoseVelocityTime()

Gal3 gtsam::Gal3::FromPoseVelocityTime ( const Pose3 pose,
const Velocity3 v,
double  t,
OptionalJacobian< 10, 6 >  H1 = {},
OptionalJacobian< 10, 3 >  H2 = {},
OptionalJacobian< 10, 1 >  H3 = {} 
)
static

Named constructor from Pose3, velocity, and time with derivatives.

Definition at line 88 of file Gal3.cpp.

◆ Hat()

Matrix5 gtsam::Gal3::Hat ( const Vector10 xi)
static

Hat operator: maps tangent vector xi to Lie algebra matrix.

Definition at line 419 of file Gal3.cpp.

◆ Identity()

static Gal3 gtsam::Gal3::Identity ( )
inlinestatic

Return the identity element.

Definition at line 141 of file Gal3.h.

◆ inverse()

Gal3 gtsam::Gal3::inverse ( ) const

Return the inverse of this element.

Definition at line 210 of file Gal3.cpp.

◆ Logmap()

Vector10 gtsam::Gal3::Logmap ( const Gal3 g,
OptionalJacobian< 10, 10 >  Hg = {} 
)
static

Logarithmic map at identity: manifold element g -> tangent vector xi.

Definition at line 273 of file Gal3.cpp.

◆ LogmapDerivative()

Matrix10 gtsam::Gal3::LogmapDerivative ( const Gal3 g)
static

Derivative of Logmap(g) w.r.t. g.

Definition at line 404 of file Gal3.cpp.

◆ matrix()

Matrix5 gtsam::Gal3::matrix ( ) const

Return 5x5 homogeneous matrix representation.

Definition at line 168 of file Gal3.cpp.

◆ operator*()

Gal3 gtsam::Gal3::operator* ( const Gal3 other) const

Group composition operator.

Definition at line 220 of file Gal3.cpp.

◆ position()

const Point3& gtsam::Gal3::position ( OptionalJacobian< 3, 10 >  H = {}) const
inline

Definition at line 101 of file Gal3.h.

◆ print()

void gtsam::Gal3::print ( const std::string &  s = "") const

Print with optional string prefix.

Definition at line 194 of file Gal3.cpp.

◆ R()

Matrix3 gtsam::Gal3::R ( ) const
inline

Return rotation matrix (Matrix3)

Definition at line 108 of file Gal3.h.

◆ r()

Vector3 gtsam::Gal3::r ( ) const
inline

Return position as Vector3.

Definition at line 111 of file Gal3.h.

◆ rotation()

const Rot3 & gtsam::Gal3::rotation ( OptionalJacobian< 3, 10 >  H = {}) const

Access rotation component (Rot3)

Definition at line 129 of file Gal3.cpp.

◆ t()

const double& gtsam::Gal3::t ( ) const
inline

Return time scalar.

Definition at line 117 of file Gal3.h.

◆ time()

const double & gtsam::Gal3::time ( OptionalJacobian< 1, 10 >  H = {}) const

Access time component (double)

Definition at line 157 of file Gal3.cpp.

◆ translation()

const Point3 & gtsam::Gal3::translation ( OptionalJacobian< 3, 10 >  H = {}) const

Access translation component (Point3)

Definition at line 138 of file Gal3.cpp.

◆ v()

const Vector3& gtsam::Gal3::v ( ) const
inline

Return velocity as Vector3.

Definition at line 114 of file Gal3.h.

◆ Vee()

Vector10 gtsam::Gal3::Vee ( const Matrix5 X)
static

Vee operator: maps Lie algebra matrix to tangent vector xi.

Definition at line 435 of file Gal3.cpp.

◆ velocity()

const Velocity3 & gtsam::Gal3::velocity ( OptionalJacobian< 3, 10 >  H = {}) const

Access velocity component (Vector3)

Definition at line 148 of file Gal3.cpp.

Friends And Related Function Documentation

◆ operator<<

GTSAM_EXPORT friend std::ostream& operator<< ( std::ostream &  os,
const Gal3 state 
)
friend

Output stream operator.

Definition at line 183 of file Gal3.cpp.

Member Data Documentation

◆ dimension

constexpr size_t gtsam::Gal3::dimension = 10
inlinestaticconstexpr

The dimension of the tangent space.

Definition at line 55 of file Gal3.h.

◆ R_

Rot3 gtsam::Gal3::R_
private

Rotation world R body.

Definition at line 47 of file Gal3.h.

◆ r_

Point3 gtsam::Gal3::r_
private

Position in world frame, n_r_b.

Definition at line 48 of file Gal3.h.

◆ t_

double gtsam::Gal3::t_
private

Time component.

Definition at line 50 of file Gal3.h.

◆ v_

Velocity3 gtsam::Gal3::v_
private

Velocity in world frame, n_v_b.

Definition at line 49 of file Gal3.h.


The documentation for this class was generated from the following files:


gtsam
Author(s):
autogenerated on Wed May 28 2025 03:14:27