GTSAM  4.0.2
C++ library for smoothing and mapping (SAM)
Classes | Public Types | Public Member Functions | Static Public Member Functions | List of all members
gtsam::Similarity3 Class Reference

#include <Similarity3.h>

Inheritance diagram for gtsam::Similarity3:
Inheritance graph
[legend]
Collaboration diagram for gtsam::Similarity3:
Collaboration graph
[legend]

Classes

struct  ChartAtOrigin
 Chart at the origin. More...
 

Public Types

enum  
 
typedef OptionalJacobian< N, N > ChartJacobian
 
typedef Eigen::Matrix< double, N, N > Jacobian
 
typedef Eigen::Matrix< double, N, 1 > TangentVector
 

Public Member Functions

const Similarity3derived () const
 
Similarity3 compose (const Similarity3 &g) const
 
Similarity3 compose (const Similarity3 &g, ChartJacobian H1, ChartJacobian 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={}) const
 
GTSAM_EXPORT SOn between (const SOn &g, DynamicJacobian H1, DynamicJacobian H2) const
 
Similarity3 inverse (ChartJacobian H) const
 
Similarity3 expmap (const TangentVector &v) const
 
Similarity3 expmap (const TangentVector &v, ChartJacobian H1, ChartJacobian H2={}) const
 expmap with optional derivatives
 
TangentVector logmap (const Similarity3 &g) const
 
TangentVector logmap (const Similarity3 &g, ChartJacobian H1, ChartJacobian H2={}) 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={}) 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={}) const
 localCoordinates with optional derivatives
 
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].
 

Static Public Member Functions

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.
 

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={}, OptionalJacobian< 3, 3 > H2={}) const
 Action on a point p is s*(R*p+t)
 
Pose3 transformFrom (const Pose3 &T) const
 
Point3 operator* (const Point3 &p) const
 
static Similarity3 Align (const Point3Pairs &abPointPairs)
 
static Similarity3 Align (const std::vector< Pose3Pair > &abPosePairs)
 

Lie Group

Matrix7 AdjointMap () const
 Project from one tangent space to another.
 
static Vector7 Logmap (const Similarity3 &s, OptionalJacobian< 7, 7 > Hm={})
 
static Similarity3 Expmap (const Vector7 &v, OptionalJacobian< 7, 7 > Hm={})
 
static Matrix4 wedge (const Vector7 &xi)
 

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.
 

Detailed Description

3D similarity transform

Member Function Documentation

◆ Align() [1/2]

static Similarity3 gtsam::Similarity3::Align ( const Point3Pairs &  abPointPairs)
static

Create Similarity3 by aligning at least three point pairs

◆ Align() [2/2]

static 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

◆ expmap()

Similarity3 gtsam::LieGroup< Similarity3 , N >::expmap ( const TangentVector &  v) const
inlineinherited

expmap as required by manifold concept Applies exponential map to v and composes with *this

◆ Expmap()

static Similarity3 gtsam::Similarity3::Expmap ( const Vector7 &  v,
OptionalJacobian< 7, 7 >  Hm = {} 
)
static

Exponential map at the identity

◆ logmap()

TangentVector gtsam::LieGroup< Similarity3 , N >::logmap ( const Similarity3 g) const
inlineinherited

logmap as required by manifold concept Applies logarithmic map to group element that takes *this to g

◆ Logmap()

static Vector7 gtsam::Similarity3::Logmap ( const Similarity3 s,
OptionalJacobian< 7, 7 >  Hm = {} 
)
static

Log map at the identity \( [R_x,R_y,R_z, t_x, t_y, t_z, \lambda] \)

◆ operator*()

Point3 gtsam::Similarity3::operator* ( const Point3 p) const

syntactic sugar for transformFrom

◆ 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()

static 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 file: