23#include <gtsam/dllexport.h>
39 typedef Rot3 Rotation;
40 typedef Point3 Translation;
62 Similarity3(
const Matrix3& R,
const Vector3& t,
double s);
78 void print(
const std::string& s)
const;
80 friend std::ostream& operator<<(std::ostream& os,
const Similarity3& p);
155 ChartJacobian H = boost::none) {
159 ChartJacobian H = boost::none) {
172 static Matrix4
wedge(
const Vector7& xi);
194 inline static size_t Dim() {
return 7; }
197 inline size_t dim()
const {
return 7; }
205 static Matrix3 GetV(Vector3 w,
double lambda);
211inline Matrix wedge<Similarity3>(
const Vector& xi) {
Base class and basic functions for Manifold types.
Base class and basic functions for Lie types.
3D rotation represented as a rotation matrix or quaternion
Global functions in a separate testing namespace.
Definition chartTesting.h:28
Vector3 Point3
As of GTSAM 4, in order to make GTSAM more lean, it is now possible to just typedef Point3 to Vector3...
Definition Point3.h:36
A manifold defines a space in which there is a notion of a linear tangent space that can be centered ...
Definition concepts.h:30
A CRTP helper class that implements Lie group methods Prerequisites: methods operator*,...
Definition Lie.h:37
Both LieGroupTraits and Testable.
Definition Lie.h:229
OptionalJacobian is an Eigen::Ref like class that can take be constructed using either a fixed size o...
Definition OptionalJacobian.h:41
A 3D pose (R,t) : (Rot3,Point3).
Definition Pose3.h:37
Rot3 is a 3D rotation represented as a rotation matrix if the preprocessor symbol GTSAM_USE_QUATERNIO...
Definition Rot3.h:58
3D similarity transform
Definition Similarity3.h:36
static Vector7 Logmap(const Similarity3 &s, OptionalJacobian< 7, 7 > Hm=boost::none)
Log map at the identity .
Definition Similarity3.cpp:256
static size_t Dim()
Dimensionality of tangent space = 7 DOF - used to autodetect sizes.
Definition Similarity3.h:194
void print(const std::string &s) const
Print with optional string.
Definition Similarity3.cpp:118
Matrix7 AdjointMap() const
Project from one tangent space to another.
Definition Similarity3.cpp:208
static Similarity3 Expmap(const Vector7 &v, OptionalJacobian< 7, 7 > Hm=boost::none)
Exponential map at the identity.
Definition Similarity3.cpp:269
static Similarity3 Identity()
Return an identity transform.
Definition Similarity3.cpp:125
Point3 translation() const
Return a GTSAM translation.
Definition Similarity3.h:188
Similarity3 inverse() const
Return the inverse.
Definition Similarity3.cpp:132
static Similarity3 Align(const Point3Pairs &abPointPairs)
Create Similarity3 by aligning at least three point pairs.
Definition Similarity3.cpp:162
Similarity3()
Default constructor.
Definition Similarity3.cpp:89
Rot3 rotation() const
Return a GTSAM rotation.
Definition Similarity3.h:185
size_t dim() const
Dimensionality of tangent space = 7 DOF.
Definition Similarity3.h:197
static Matrix4 wedge(const Vector7 &xi)
wedge for Similarity3:
Definition Similarity3.cpp:198
Matrix4 matrix() const
Calculate 4*4 matrix group equivalent.
Definition Similarity3.cpp:286
bool equals(const Similarity3 &sim, double tol) const
Compare with tolerance.
Definition Similarity3.cpp:109
double scale() const
Return the scale.
Definition Similarity3.h:191
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).
Definition Similarity3.cpp:138
Similarity3 operator*(const Similarity3 &S) const
Composition.
Definition Similarity3.cpp:128
bool operator==(const Similarity3 &other) const
Exact equality.
Definition Similarity3.cpp:114
Chart at the origin.
Definition Similarity3.h:153