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>
22 #include <gtsam/geometry/Point3.h>
23 #include <gtsam/geometry/Pose3.h>
24 #include <gtsam/base/Lie.h>
25 #include <gtsam/base/Manifold.h>
26 #include <gtsam/dllexport.h>
27 
28 
29 namespace gtsam {
30 
31 // Forward declarations
32 class Pose3;
33 
37 class Similarity3: public LieGroup<Similarity3, 7> {
38 
41  typedef Rot3 Rotation;
44 
45 private:
48  double s_;
49 
50 public:
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 
156  struct ChartAtOrigin {
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 
218 private:
220  static Matrix3 GetV(Vector3 w, double lambda);
221 
223 };
224 
225 template<>
227  return Similarity3::wedge(xi);
228 }
229 
230 template<>
231 struct traits<Similarity3> : public internal::LieGroup<Similarity3> {};
232 
233 template<>
234 struct traits<const Similarity3> : public internal::LieGroup<Similarity3> {};
235 
236 } // namespace gtsam
GTSAM_EXPORT bool operator==(const Similarity3 &other) const
Exact equality.
GTSAM_EXPORT const Matrix4 matrix() const
Calculate 4*4 matrix group equivalent.
static size_t Dim()
Dimensionality of tangent space = 7 DOF - used to autodetect sizes.
Definition: Similarity3.h:205
static GTSAM_EXPORT Vector7 Logmap(const Similarity3 &s, OptionalJacobian< 7, 7 > Hm=boost::none)
Eigen::Vector3d Vector3
Definition: Vector.h:43
static GTSAM_EXPORT Similarity3 Expmap(const Vector7 &v, OptionalJacobian< 7, 7 > Hm=boost::none)
static GTSAM_EXPORT Similarity3 identity()
Return an identity transform.
ArrayXcf v
Definition: Cwise_arg.cpp:1
Eigen::MatrixXd Matrix
Definition: base/Matrix.h:43
Rot2 R(Rot2::fromAngle(0.1))
double scale() const
Return the scale.
Definition: Similarity3.h:196
static Vector7 Local(const Similarity3 &other, ChartJacobian H=boost::none)
Definition: Similarity3.h:160
static GTSAM_EXPORT Matrix4 wedge(const Vector7 &xi)
set noclip points set clip one set noclip two set bar set border lt lw set xdata set ydata set zdata set x2data set y2data set boxwidth set dummy y set format x g set format y g set format x2 g set format y2 g set format z g set angles radians set nogrid set key title set key left top Right noreverse box linetype linewidth samplen spacing width set nolabel set noarrow set nologscale set logscale x set set pointsize set encoding default set nopolar set noparametric set set set set surface set nocontour set clabel set mapping cartesian set nohidden3d set cntrparam order set cntrparam linear set cntrparam levels auto set cntrparam points set size set set xzeroaxis lt lw set x2zeroaxis lt lw set yzeroaxis lt lw set y2zeroaxis lt lw set tics in set ticslevel set tics set mxtics default set mytics default set mx2tics default set my2tics default set xtics border mirror norotate autofreq set ytics border mirror norotate autofreq set ztics border nomirror norotate autofreq set nox2tics set noy2tics set timestamp bottom norotate set rrange[*:*] noreverse nowriteback set trange[*:*] noreverse nowriteback set urange[*:*] noreverse nowriteback set vrange[*:*] noreverse nowriteback set xlabel matrix size set x2label set timefmt d m y n H
GTSAM_EXPORT bool equals(const Similarity3 &sim, double tol) const
Compare with tolerance.
Matrix wedge< Similarity3 >(const Vector &xi)
Definition: Similarity3.h:226
size_t dim() const
Dimensionality of tangent space = 7 DOF.
Definition: Similarity3.h:210
Eigen::VectorXd Vector
Definition: Vector.h:38
Key S(std::uint64_t j)
GTSAM_EXPORT Similarity3 operator*(const Similarity3 &S) const
Composition.
Base class and basic functions for Manifold types.
GTSAM_EXPORT Similarity3()
Default constructor.
Definition: Similarity3.cpp:87
GTSAM_EXPORT void print(const std::string &s) const
Print with optional string.
static Similarity3 Retract(const Vector7 &v, ChartJacobian H=boost::none)
Definition: Similarity3.h:157
const Point3 & translation() const
Return a GTSAM translation.
Definition: Similarity3.h:191
RealScalar s
static GTSAM_EXPORT Similarity3 Align(const std::vector< Point3Pair > &abPointPairs)
RowVector3d w
Base class and basic functions for Lie types.
cout<< "The eigenvalues of A are:"<< endl<< ces.eigenvalues()<< endl;cout<< "The matrix of eigenvectors, V, is:"<< endl<< ces.eigenvectors()<< endl<< endl;complex< float > lambda
Vector xi
Definition: testPose2.cpp:150
traits
Definition: chartTesting.h:28
GTSAM_EXPORT Similarity3 inverse() const
Return the inverse.
const Rot3 & rotation() const
Return a GTSAM rotation.
Definition: Similarity3.h:186
ofstream os("timeSchurFactors.csv")
Both LieGroupTraits and Testable.
Definition: Lie.h:228
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)
3D Point
float * p
static Matrix3 GetV(Vector3 w, double lambda)
Calculate expmap and logmap coefficients.
const G double tol
Definition: Group.h:83
Vector3 Point3
Definition: Point3.h:35
3D Pose
Point2 t(10, 10)
GTSAM_EXPORT Matrix7 AdjointMap() const
Project from one tangent space to another.
3D rotation represented as a rotation matrix or quaternion
GTSAM_EXPORT friend std::ostream & operator<<(std::ostream &os, const Similarity3 &p)


gtsam
Author(s):
autogenerated on Sat May 8 2021 02:44:02