gtsam 4.1.1
gtsam
Similarity3.h
Go to the documentation of this file.
1/* ----------------------------------------------------------------------------
2
3 * GTSAM Copyright 2010, Georgia Tech Research Corporation,
4 * Atlanta, Georgia 30332-0415
5 * All Rights Reserved
6 * Authors: Frank Dellaert, et al. (see THANKS for the full author list)
7
8 * See LICENSE for the license information
9
10 * -------------------------------------------------------------------------- */
11
19#pragma once
20
21#include <gtsam/geometry/Rot3.h>
24#include <gtsam/base/Lie.h>
25#include <gtsam/base/Manifold.h>
26#include <gtsam/dllexport.h>
27
28
29namespace gtsam {
30
31// Forward declarations
32class Pose3;
33
37class Similarity3: public LieGroup<Similarity3, 7> {
38
41 typedef Rot3 Rotation;
42 typedef Point3 Translation;
44
45private:
46 Rot3 R_;
47 Point3 t_;
48 double s_;
49
50public:
51
54
56 GTSAM_EXPORT Similarity3();
57
59 GTSAM_EXPORT Similarity3(double s);
60
62 GTSAM_EXPORT Similarity3(const Rot3& R, const Point3& t, double s);
63
65 GTSAM_EXPORT Similarity3(const Matrix3& R, const Vector3& t, double s);
66
68 GTSAM_EXPORT Similarity3(const Matrix4& T);
69
73
75 GTSAM_EXPORT bool equals(const Similarity3& sim, double tol) const;
76
78 GTSAM_EXPORT bool operator==(const Similarity3& other) const;
79
81 GTSAM_EXPORT void print(const std::string& s) const;
82
83 GTSAM_EXPORT friend std::ostream &operator<<(std::ostream &os, const Similarity3& p);
84
88
90 GTSAM_EXPORT static Similarity3 identity();
91
93 GTSAM_EXPORT Similarity3 operator*(const Similarity3& S) const;
94
96 GTSAM_EXPORT Similarity3 inverse() const;
97
101
103 GTSAM_EXPORT Point3 transformFrom(const Point3& p, //
104 OptionalJacobian<3, 7> H1 = boost::none, //
105 OptionalJacobian<3, 3> H2 = boost::none) const;
106
118 GTSAM_EXPORT Pose3 transformFrom(const Pose3& T) const;
119
121 GTSAM_EXPORT Point3 operator*(const Point3& p) const;
122
126 GTSAM_EXPORT static Similarity3 Align(const std::vector<Point3Pair>& abPointPairs);
127
138 GTSAM_EXPORT static Similarity3 Align(const std::vector<Pose3Pair>& abPosePairs);
139
143
147 GTSAM_EXPORT static Vector7 Logmap(const Similarity3& s, //
148 OptionalJacobian<7, 7> Hm = boost::none);
149
152 GTSAM_EXPORT static Similarity3 Expmap(const Vector7& v, //
153 OptionalJacobian<7, 7> Hm = boost::none);
154
157 static Similarity3 Retract(const Vector7& v, ChartJacobian H = boost::none) {
158 return Similarity3::Expmap(v, H);
159 }
160 static Vector7 Local(const Similarity3& other, ChartJacobian H = boost::none) {
161 return Similarity3::Logmap(other, H);
162 }
163 };
164
166
173 GTSAM_EXPORT static Matrix4 wedge(const Vector7& xi);
174
176 GTSAM_EXPORT Matrix7 AdjointMap() const;
177
181
183 GTSAM_EXPORT const Matrix4 matrix() const;
184
186 const Rot3& rotation() const {
187 return R_;
188 }
189
191 const Point3& translation() const {
192 return t_;
193 }
194
196 double scale() const {
197 return s_;
198 }
199
202 GTSAM_EXPORT operator Pose3() const;
203
205 inline static size_t Dim() {
206 return 7;
207 }
208
210 inline size_t dim() const {
211 return 7;
212 }
213
217
218private:
220 static Matrix3 GetV(Vector3 w, double lambda);
221
223};
224
225template<>
226inline Matrix wedge<Similarity3>(const Vector& xi) {
227 return Similarity3::wedge(xi);
228}
229
230template<>
231struct traits<Similarity3> : public internal::LieGroup<Similarity3> {};
232
233template<>
234struct traits<const Similarity3> : public internal::LieGroup<Similarity3> {};
235
236} // namespace gtsam
Base class and basic functions for Manifold types.
Base class and basic functions for Lie types.
3D Point
3D Pose
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
Definition: Pose3.h:37
Definition: Rot3.h:59
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