gtsam 4.2.0
gtsam
Loading...
Searching...
No Matches
gtsam::Similarity3 Class Reference

Detailed Description

3D similarity transform

+ Inheritance diagram for gtsam::Similarity3:

Testable

bool equals (const Similarity3 &sim, double tol) const
 Compare with tolerance.
 
bool operator== (const Similarity3 &other) const
 Exact equality.
 
void print (const std::string &s) const
 Print with optional string.
 
std::ostream & operator<< (std::ostream &os, const Similarity3 &p)
 

Group

Similarity3 operator* (const Similarity3 &S) const
 Composition.
 
Similarity3 inverse () const
 Return the inverse.
 
static Similarity3 Identity ()
 Return an identity transform.
 

Group action on Point3

Point3 transformFrom (const Point3 &p, OptionalJacobian< 3, 7 > H1=boost::none, OptionalJacobian< 3, 3 > H2=boost::none) const
 Action on a point p is s*(R*p+t)
 
Pose3 transformFrom (const Pose3 &T) const
 Action on a pose T.
 
Point3 operator* (const Point3 &p) const
 syntactic sugar for transformFrom
 
static Similarity3 Align (const Point3Pairs &abPointPairs)
 Create Similarity3 by aligning at least three point pairs.
 
static Similarity3 Align (const std::vector< Pose3Pair > &abPosePairs)
 Create the Similarity3 object that aligns at least two pose pairs.
 

Lie Group

Matrix7 AdjointMap () const
 Project from one tangent space to another.
 
static Vector7 Logmap (const Similarity3 &s, OptionalJacobian< 7, 7 > Hm=boost::none)
 Log map at the identity \( [R_x,R_y,R_z, t_x, t_y, t_z, \lambda] \).
 
static Similarity3 Expmap (const Vector7 &v, OptionalJacobian< 7, 7 > Hm=boost::none)
 Exponential map at the identity.
 
static Matrix4 wedge (const Vector7 &xi)
 wedge for Similarity3:
 

Standard interface

Matrix4 matrix () const
 Calculate 4*4 matrix group equivalent.
 
Rot3 rotation () const
 Return a GTSAM rotation.
 
Point3 translation () const
 Return a GTSAM translation.
 
double scale () const
 Return the scale.
 
size_t dim () const
 Dimensionality of tangent space = 7 DOF.
 
static size_t Dim ()
 Dimensionality of tangent space = 7 DOF - used to autodetect sizes.
 

Public Member Functions

Constructors
 Similarity3 ()
 Default constructor.
 
 Similarity3 (double s)
 Construct pure scaling.
 
 Similarity3 (const Rot3 &R, const Point3 &t, double s)
 Construct from GTSAM types.
 
 Similarity3 (const Matrix3 &R, const Vector3 &t, double s)
 Construct from Eigen types.
 
 Similarity3 (const Matrix4 &T)
 Construct from matrix [R t; 0 s^-1].
 
- Public Member Functions inherited from gtsam::LieGroup< Similarity3, 7 >
const Similarity3derived () const
 
Similarity3 compose (const Similarity3 &g) const
 
Similarity3 compose (const Similarity3 &g, ChartJacobian H1, ChartJacobian H2=boost::none) const
 
SOn compose (const SOn &g, DynamicJacobian H1, DynamicJacobian H2) const
 
GTSAM_EXPORT SOn compose (const SOn &g, DynamicJacobian H1, DynamicJacobian H2) const
 
Similarity3 between (const Similarity3 &g) const
 
Similarity3 between (const Similarity3 &g, ChartJacobian H1, ChartJacobian H2=boost::none) const
 
SOn between (const SOn &g, DynamicJacobian H1, DynamicJacobian H2) const
 
GTSAM_EXPORT SOn between (const SOn &g, DynamicJacobian H1, DynamicJacobian H2) const
 
Similarity3 inverse (ChartJacobian H) const
 
Similarity3 expmap (const TangentVector &v) const
 expmap as required by manifold concept Applies exponential map to v and composes with *this
 
Similarity3 expmap (const TangentVector &v, ChartJacobian H1, ChartJacobian H2=boost::none) const
 expmap with optional derivatives
 
TangentVector logmap (const Similarity3 &g) const
 logmap as required by manifold concept Applies logarithmic map to group element that takes *this to g
 
TangentVector logmap (const Similarity3 &g, ChartJacobian H1, ChartJacobian H2=boost::none) const
 logmap with optional derivatives
 
Similarity3 retract (const TangentVector &v) const
 retract as required by manifold concept: applies v at *this
 
Similarity3 retract (const TangentVector &v, ChartJacobian H1, ChartJacobian H2=boost::none) const
 retract with optional derivatives
 
TangentVector localCoordinates (const Similarity3 &g) const
 localCoordinates as required by manifold concept: finds tangent vector between *this and g
 
TangentVector localCoordinates (const Similarity3 &g, ChartJacobian H1, ChartJacobian H2=boost::none) const
 localCoordinates with optional derivatives
 

Classes

struct  ChartAtOrigin
 Chart at the origin. More...
 

Additional Inherited Members

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

Member Function Documentation

◆ Align()

Similarity3 gtsam::Similarity3::Align ( const std::vector< Pose3Pair > &  abPosePairs)
static

Create the Similarity3 object that aligns at least two pose pairs.

Each pair is of the form (aTi, bTi). Given a list of pairs in frame a, and a list of pairs in frame b, Align() will compute the best-fit Similarity3 aSb transformation to align them. First, the rotation aRb will be computed as the average (Karcher mean) of many estimates aRb (from each pair). Afterwards, the scale factor will be computed using the algorithm described here: http://www5.informatik.uni-erlangen.de/Forschung/Publikationen/2005/Zinsser05-PSR.pdf

◆ transformFrom()

Pose3 gtsam::Similarity3::transformFrom ( const Pose3 T) const

Action on a pose T.

|Rs ts| |R t| |Rs*R Rs*t+ts| |0 1/s| * |0 1| = | 0 1/s |, the result is still a Sim3 object. To retrieve a Pose3, we normalized the scale value into 1. |Rs*R Rs*t+ts| |Rs*R s(Rs*t+ts)| | 0 1/s | = | 0 1 |

This group action satisfies the compatibility condition. For more details, refer to: https://en.wikipedia.org/wiki/Group_action

◆ wedge()

Matrix4 gtsam::Similarity3::wedge ( const Vector7 &  xi)
static

wedge for Similarity3:

Parameters
xi7-dim twist (w,u,lambda) where
Returns
4*4 element of Lie algebra that can be exponentiated TODO(frank): rename to Hat, make part of traits

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