#include <Similarity3.h>
Classes | |
struct | ChartAtOrigin |
Chart at the origin. More... | |
Public Member Functions | |
Constructors | |
GTSAM_EXPORT | Similarity3 () |
Default constructor. More... | |
GTSAM_EXPORT | Similarity3 (double s) |
Construct pure scaling. More... | |
GTSAM_EXPORT | Similarity3 (const Rot3 &R, const Point3 &t, double s) |
Construct from GTSAM types. More... | |
GTSAM_EXPORT | Similarity3 (const Matrix3 &R, const Vector3 &t, double s) |
Construct from Eigen types. More... | |
GTSAM_EXPORT | Similarity3 (const Matrix4 &T) |
Construct from matrix [R t; 0 s^-1]. More... | |
Public Member Functions inherited from gtsam::LieGroup< Similarity3, 7 > | |
Similarity3 | between (const Similarity3 &g) const |
Similarity3 | between (const Similarity3 &g, ChartJacobian H1, ChartJacobian H2=boost::none) const |
Similarity3 | compose (const Similarity3 &g) const |
Similarity3 | compose (const Similarity3 &g, ChartJacobian H1, ChartJacobian H2=boost::none) const |
const Similarity3 & | derived () const |
Similarity3 | expmap (const TangentVector &v) const |
Similarity3 | expmap (const TangentVector &v, ChartJacobian H1, ChartJacobian H2=boost::none) const |
expmap with optional derivatives More... | |
Similarity3 | inverse (ChartJacobian H) const |
TangentVector | localCoordinates (const Similarity3 &g) const |
localCoordinates as required by manifold concept: finds tangent vector between *this and g More... | |
TangentVector | localCoordinates (const Similarity3 &g, ChartJacobian H1, ChartJacobian H2=boost::none) const |
localCoordinates with optional derivatives More... | |
TangentVector | logmap (const Similarity3 &g) const |
TangentVector | logmap (const Similarity3 &g, ChartJacobian H1, ChartJacobian H2=boost::none) const |
logmap with optional derivatives More... | |
Similarity3 | retract (const TangentVector &v) const |
retract as required by manifold concept: applies v at *this More... | |
Similarity3 | retract (const TangentVector &v, ChartJacobian H1, ChartJacobian H2=boost::none) const |
retract with optional derivatives More... | |
Private Types | |
Pose Concept | |
typedef Rot3 | Rotation |
typedef Point3 | Translation |
Static Private Member Functions | |
Helper functions | |
static Matrix3 | GetV (Vector3 w, double lambda) |
Calculate expmap and logmap coefficients. More... | |
Private Attributes | |
Rot3 | R_ |
double | s_ |
Point3 | t_ |
Testable | |
GTSAM_EXPORT bool | equals (const Similarity3 &sim, double tol) const |
Compare with tolerance. More... | |
GTSAM_EXPORT bool | operator== (const Similarity3 &other) const |
Exact equality. More... | |
GTSAM_EXPORT void | print (const std::string &s) const |
Print with optional string. More... | |
GTSAM_EXPORT friend std::ostream & | operator<< (std::ostream &os, const Similarity3 &p) |
Group | |
GTSAM_EXPORT Similarity3 | operator* (const Similarity3 &S) const |
Composition. More... | |
GTSAM_EXPORT Similarity3 | inverse () const |
Return the inverse. More... | |
static GTSAM_EXPORT Similarity3 | identity () |
Return an identity transform. More... | |
Group action on Point3 | |
GTSAM_EXPORT 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) More... | |
GTSAM_EXPORT Pose3 | transformFrom (const Pose3 &T) const |
GTSAM_EXPORT Point3 | operator* (const Point3 &p) const |
static GTSAM_EXPORT Similarity3 | Align (const std::vector< Point3Pair > &abPointPairs) |
static GTSAM_EXPORT Similarity3 | Align (const std::vector< Pose3Pair > &abPosePairs) |
Lie Group | |
GTSAM_EXPORT Matrix7 | AdjointMap () const |
Project from one tangent space to another. More... | |
static GTSAM_EXPORT Vector7 | Logmap (const Similarity3 &s, OptionalJacobian< 7, 7 > Hm=boost::none) |
static GTSAM_EXPORT Similarity3 | Expmap (const Vector7 &v, OptionalJacobian< 7, 7 > Hm=boost::none) |
static GTSAM_EXPORT Matrix4 | wedge (const Vector7 &xi) |
Standard interface | |
GTSAM_EXPORT const Matrix4 | matrix () const |
Calculate 4*4 matrix group equivalent. More... | |
const Rot3 & | rotation () const |
Return a GTSAM rotation. More... | |
const Point3 & | translation () const |
Return a GTSAM translation. More... | |
double | scale () const |
Return the scale. More... | |
GTSAM_EXPORT | operator Pose3 () const |
size_t | dim () const |
Dimensionality of tangent space = 7 DOF. More... | |
static size_t | Dim () |
Dimensionality of tangent space = 7 DOF - used to autodetect sizes. More... | |
Additional Inherited Members | |
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 |
Static Public Member Functions inherited from gtsam::LieGroup< Similarity3, 7 > | |
static TangentVector | LocalCoordinates (const Similarity3 &g) |
LocalCoordinates at origin: possible in Lie group because it has an identity. More... | |
static TangentVector | LocalCoordinates (const Similarity3 &g, ChartJacobian H) |
LocalCoordinates at origin with optional derivative. More... | |
static Similarity3 | Retract (const TangentVector &v) |
Retract at origin: possible in Lie group because it has an identity. More... | |
static Similarity3 | Retract (const TangentVector &v, ChartJacobian H) |
Retract at origin with optional derivative. More... | |
3D similarity transform
Definition at line 37 of file Similarity3.h.
|
private |
Definition at line 41 of file Similarity3.h.
|
private |
Definition at line 42 of file Similarity3.h.
gtsam::Similarity3::Similarity3 | ( | ) |
Default constructor.
Definition at line 87 of file Similarity3.cpp.
gtsam::Similarity3::Similarity3 | ( | double | s | ) |
Construct pure scaling.
Definition at line 91 of file Similarity3.cpp.
Construct from GTSAM types.
Definition at line 95 of file Similarity3.cpp.
gtsam::Similarity3::Similarity3 | ( | const Matrix3 & | R, |
const Vector3 & | t, | ||
double | s | ||
) |
Construct from Eigen types.
Definition at line 99 of file Similarity3.cpp.
gtsam::Similarity3::Similarity3 | ( | const Matrix4 & | T | ) |
Construct from matrix [R t; 0 s^-1].
Definition at line 103 of file Similarity3.cpp.
Matrix7 gtsam::Similarity3::AdjointMap | ( | ) | const |
Project from one tangent space to another.
Definition at line 206 of file Similarity3.cpp.
|
static |
Create Similarity3 by aligning at least three point pairs
Definition at line 160 of file Similarity3.cpp.
|
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
Definition at line 173 of file Similarity3.cpp.
|
inlinestatic |
Dimensionality of tangent space = 7 DOF - used to autodetect sizes.
Definition at line 205 of file Similarity3.h.
|
inline |
Dimensionality of tangent space = 7 DOF.
Definition at line 210 of file Similarity3.h.
bool gtsam::Similarity3::equals | ( | const Similarity3 & | sim, |
double | tol | ||
) | const |
Compare with tolerance.
Definition at line 107 of file Similarity3.cpp.
|
static |
Exponential map at the identity
Definition at line 267 of file Similarity3.cpp.
|
staticprivate |
Calculate expmap and logmap coefficients.
Definition at line 218 of file Similarity3.cpp.
|
static |
Return an identity transform.
Definition at line 123 of file Similarity3.cpp.
Similarity3 gtsam::Similarity3::inverse | ( | ) | const |
Return the inverse.
Definition at line 130 of file Similarity3.cpp.
|
static |
Log map at the identity
Definition at line 254 of file Similarity3.cpp.
const Matrix4 gtsam::Similarity3::matrix | ( | ) | const |
Calculate 4*4 matrix group equivalent.
Definition at line 284 of file Similarity3.cpp.
gtsam::Similarity3::operator Pose3 | ( | ) | const |
Convert to a rigid body pose (R, s*t) TODO(frank): why is this here? Red flag! Definitely don't have it as a cast.
Definition at line 291 of file Similarity3.cpp.
Similarity3 gtsam::Similarity3::operator* | ( | const Similarity3 & | S | ) | const |
Composition.
Definition at line 126 of file Similarity3.cpp.
syntactic sugar for transformFrom
Definition at line 156 of file Similarity3.cpp.
bool gtsam::Similarity3::operator== | ( | const Similarity3 & | other | ) | const |
Exact equality.
Definition at line 112 of file Similarity3.cpp.
void gtsam::Similarity3::print | ( | const std::string & | s | ) | const |
Print with optional string.
Definition at line 116 of file Similarity3.cpp.
|
inline |
Return a GTSAM rotation.
Definition at line 186 of file Similarity3.h.
|
inline |
Return the scale.
Definition at line 196 of file Similarity3.h.
Point3 gtsam::Similarity3::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)
Definition at line 136 of file Similarity3.cpp.
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
Definition at line 150 of file Similarity3.cpp.
|
inline |
Return a GTSAM translation.
Definition at line 191 of file Similarity3.h.
|
static |
wedge for Similarity3:
xi | 7-dim twist (w,u,lambda) where |
Definition at line 196 of file Similarity3.cpp.
|
friend |
Definition at line 278 of file Similarity3.cpp.
|
private |
Definition at line 46 of file Similarity3.h.
|
private |
Definition at line 48 of file Similarity3.h.
|
private |
Definition at line 47 of file Similarity3.h.