|
|
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) |
|
|
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:
|
|
|
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.
|
|
|
| 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].
|
|
SOn | compose (const SOn &g, DynamicJacobian H1, DynamicJacobian H2) const |
|
SOn | between (const SOn &g, DynamicJacobian H1, DynamicJacobian H2) const |
|
GTSAM_EXPORT SOn | compose (const SOn &g, DynamicJacobian H1, DynamicJacobian H2) const |
|
GTSAM_EXPORT SOn | between (const SOn &g, DynamicJacobian H1, DynamicJacobian H2) const |
|
const Similarity3 & | derived () 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
|
|
TangentVector | logmap (const Similarity3 &g) const |
| | logmap as required by manifold concept Applies logarithmic map to group element that takes *this to g
|
|
Similarity3 | retract (const TangentVector &v) const |
| | retract as required by manifold concept: applies v at *this
|
|
TangentVector | localCoordinates (const Similarity3 &g) const |
| | localCoordinates as required by manifold concept: finds tangent vector between *this and g
|
|
|
static Similarity3 | Retract (const TangentVector &v) |
| | Retract at origin: possible in Lie group because it has an identity.
|
|
static TangentVector | LocalCoordinates (const Similarity3 &g) |
| | LocalCoordinates at origin: possible in Lie group because it has an identity.
|
| enum | |
|
typedef OptionalJacobian< N, N > | ChartJacobian |
|
typedef Eigen::Matrix< double, N, N > | Jacobian |
|
typedef Eigen::Matrix< double, N, 1 > | TangentVector |
◆ Align()
| Similarity3 gtsam::Similarity3::Align |
( |
const std::vector< Pose3Pair > & | abPosePairs | ) |
|
|
static |
◆ 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
-
| xi | 7-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: