26#include <gtsam/dllexport.h>
42 typedef Point3 Translation;
65 GTSAM_EXPORT
Similarity3(
const Matrix3& R,
const Vector3& t,
double s);
81 GTSAM_EXPORT
void print(
const std::string& s)
const;
83 GTSAM_EXPORT
friend std::ostream &operator<<(std::ostream &os,
const Similarity3& p);
138 GTSAM_EXPORT
static Similarity3 Align(
const std::vector<Pose3Pair>& abPosePairs);
173 GTSAM_EXPORT
static Matrix4
wedge(
const Vector7& xi);
183 GTSAM_EXPORT
const Matrix4
matrix()
const;
202 GTSAM_EXPORT
operator Pose3()
const;
205 inline static size_t Dim() {
210 inline size_t dim()
const {
220 static Matrix3 GetV(Vector3 w,
double lambda);
226inline 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:35
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:39
3D similarity transform
Definition: Similarity3.h:37
static GTSAM_EXPORT Vector7 Logmap(const Similarity3 &s, OptionalJacobian< 7, 7 > Hm=boost::none)
Log map at the identity .
Definition: Similarity3.cpp:254
static size_t Dim()
Dimensionality of tangent space = 7 DOF - used to autodetect sizes.
Definition: Similarity3.h:205
GTSAM_EXPORT void print(const std::string &s) const
Print with optional string.
Definition: Similarity3.cpp:116
GTSAM_EXPORT Matrix7 AdjointMap() const
Project from one tangent space to another.
Definition: Similarity3.cpp:206
static GTSAM_EXPORT Similarity3 Expmap(const Vector7 &v, OptionalJacobian< 7, 7 > Hm=boost::none)
Exponential map at the identity.
Definition: Similarity3.cpp:267
static GTSAM_EXPORT Similarity3 identity()
Return an identity transform.
Definition: Similarity3.cpp:123
static GTSAM_EXPORT Similarity3 Align(const std::vector< Point3Pair > &abPointPairs)
Create Similarity3 by aligning at least three point pairs.
const Rot3 & rotation() const
Return a GTSAM rotation.
Definition: Similarity3.h:186
GTSAM_EXPORT Similarity3 inverse() const
Return the inverse.
Definition: Similarity3.cpp:130
GTSAM_EXPORT Similarity3()
Default constructor.
Definition: Similarity3.cpp:87
size_t dim() const
Dimensionality of tangent space = 7 DOF.
Definition: Similarity3.h:210
GTSAM_EXPORT const Matrix4 matrix() const
Calculate 4*4 matrix group equivalent.
Definition: Similarity3.cpp:284
static GTSAM_EXPORT Matrix4 wedge(const Vector7 &xi)
wedge for Similarity3:
Definition: Similarity3.cpp:196
GTSAM_EXPORT bool equals(const Similarity3 &sim, double tol) const
Compare with tolerance.
Definition: Similarity3.cpp:107
double scale() const
Return the scale.
Definition: Similarity3.h:196
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)
Definition: Similarity3.cpp:136
GTSAM_EXPORT Similarity3 operator*(const Similarity3 &S) const
Composition.
Definition: Similarity3.cpp:126
GTSAM_EXPORT bool operator==(const Similarity3 &other) const
Exact equality.
Definition: Similarity3.cpp:112
const Point3 & translation() const
Return a GTSAM translation.
Definition: Similarity3.h:191
Chart at the origin.
Definition: Similarity3.h:156