Similarity2.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 
18 #pragma once
19 
20 #include <gtsam/base/Lie.h>
21 #include <gtsam/base/Manifold.h>
22 #include <gtsam/dllexport.h>
23 #include <gtsam/geometry/Point2.h>
24 #include <gtsam/geometry/Pose2.h>
25 #include <gtsam/geometry/Rot2.h>
26 
27 namespace gtsam {
28 
29 // Forward declarations
30 class Pose2;
31 
35 class GTSAM_EXPORT Similarity2 : public LieGroup<Similarity2, 4> {
38  typedef Rot2 Rotation;
41 
42  private:
45  double s_;
46 
47  public:
50 
52  Similarity2();
53 
55  Similarity2(double s);
56 
58  Similarity2(const Rot2& R, const Point2& t, double s);
59 
61  Similarity2(const Matrix2& R, const Vector2& t, double s);
62 
64  Similarity2(const Matrix3& T);
65 
69 
71  bool equals(const Similarity2& sim, double tol) const;
72 
74  bool operator==(const Similarity2& other) const;
75 
77  void print(const std::string& s) const;
78 
79  friend std::ostream& operator<<(std::ostream& os, const Similarity2& p);
80 
84 
86  static Similarity2 Identity();
87 
89  Similarity2 operator*(const Similarity2& S) const;
90 
92  Similarity2 inverse() const;
93 
97 
99  Point2 transformFrom(const Point2& p) const;
100 
112  Pose2 transformFrom(const Pose2& T) const;
113 
114  /* syntactic sugar for transformFrom */
115  Point2 operator*(const Point2& p) const;
116 
120  static Similarity2 Align(const Point2Pairs& abPointPairs);
121 
135  static Similarity2 Align(const Pose2Pairs& abPosePairs);
136 
140 
145  static Vector4 Logmap(const Similarity2& S, //
146  OptionalJacobian<4, 4> Hm = {});
147 
149  static Similarity2 Expmap(const Vector4& v, //
150  OptionalJacobian<4, 4> Hm = {});
151 
153  struct ChartAtOrigin {
154  static Similarity2 Retract(const Vector4& v,
155  ChartJacobian H = {}) {
156  return Similarity2::Expmap(v, H);
157  }
158  static Vector4 Local(const Similarity2& other,
159  ChartJacobian H = {}) {
160  return Similarity2::Logmap(other, H);
161  }
162  };
163 
165  Matrix4 AdjointMap() const;
166 
168 
172 
174  Matrix3 matrix() const;
175 
177  Rot2 rotation() const { return R_; }
178 
180  Point2 translation() const { return t_; }
181 
183  double scale() const { return s_; }
184 
186  inline static size_t Dim() { return 4; }
187 
189  inline size_t dim() const { return 4; }
190 
192 };
193 
194 template <>
195 struct traits<Similarity2> : public internal::LieGroup<Similarity2> {};
196 
197 template <>
198 struct traits<const Similarity2> : public internal::LieGroup<Similarity2> {};
199 
200 } // namespace gtsam
void print(const Matrix &A, const string &s, ostream &stream)
Definition: Matrix.cpp:155
std::ostream & operator<<(std::ostream &os, const Dih6 &m)
Definition: testGroup.cpp:109
size_t dim() const
Dimensionality of tangent space = 4 DOF.
Definition: Similarity2.h:189
Vector2 Point2
Definition: Point2.h:32
Rot2 R(Rot2::fromAngle(0.1))
static Similarity2 Retract(const Vector4 &v, ChartJacobian H={})
Definition: Similarity2.h:154
bool operator==(const Matrix &A, const Matrix &B)
Definition: base/Matrix.h:99
Pose2_ Expmap(const Vector3_ &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
DiscreteKey S(1, 2)
Point2 operator*(double s, const Point2 &p)
multiply with scalar
Definition: Point2.h:52
EIGEN_DEVICE_FUNC const InverseReturnType inverse() const
std::vector< Point2Pair > Point2Pairs
Definition: Point2.h:38
Point3_ transformFrom(const Pose3_ &x, const Point3_ &p)
std::vector< Pose2Pair > Pose2Pairs
Definition: Pose2.h:362
Point2 translation() const
Return a GTSAM translation.
Definition: Similarity2.h:180
Base class and basic functions for Manifold types.
Array< int, Dynamic, 1 > v
double scale() const
Return the scale.
Definition: Similarity2.h:183
static Vector4 Local(const Similarity2 &other, ChartJacobian H={})
Definition: Similarity2.h:158
RealScalar s
Rot2 rotation() const
Return a GTSAM rotation.
Definition: Similarity2.h:177
Base class and basic functions for Lie types.
traits
Definition: chartTesting.h:28
static Vector4 Logmap(const Similarity2 &S, OptionalJacobian< 4, 4 > Hm={})
ofstream os("timeSchurFactors.csv")
Both LieGroupTraits and Testable.
Definition: Lie.h:229
static size_t Dim()
Dimensionality of tangent space = 4 DOF - used to autodetect sizes.
Definition: Similarity2.h:186
static Similarity2 Expmap(const Vector4 &v, OptionalJacobian< 4, 4 > Hm={})
Exponential map at the identity.
float * p
const G double tol
Definition: Group.h:86
2D Pose
Map< Matrix< T, Dynamic, Dynamic, ColMajor >, 0, OuterStride<> > matrix(T *data, int rows, int cols, int stride)
2D Point
2D rotation
Point2 t(10, 10)
static Similarity2 Align(const Point2Pairs &d_abPointPairs, const Rot2 &aRb, const Point2Pair &centroids)
This method estimates the similarity transform from differences point pairs, given a known or estimat...
Definition: Similarity2.cpp:74


gtsam
Author(s):
autogenerated on Tue Jul 4 2023 02:35:43