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  GTSAM_EXPORT friend std::ostream& operator<<(std::ostream& os,
80  const Similarity2& p);
81 
85 
87  static Similarity2 Identity();
88 
90  Similarity2 operator*(const Similarity2& S) const;
91 
93  Similarity2 inverse() const;
94 
98 
100  Point2 transformFrom(const Point2& p) const;
101 
113  Pose2 transformFrom(const Pose2& T) const;
114 
115  /* syntactic sugar for transformFrom */
116  Point2 operator*(const Point2& p) const;
117 
121  static Similarity2 Align(const Point2Pairs& abPointPairs);
122 
136  static Similarity2 Align(const Pose2Pairs& abPosePairs);
137 
141 
146  static Vector4 Logmap(const Similarity2& S, //
147  OptionalJacobian<4, 4> Hm = {});
148 
150  static Similarity2 Expmap(const Vector4& v, //
151  OptionalJacobian<4, 4> Hm = {});
152 
154  struct ChartAtOrigin {
155  static Similarity2 Retract(const Vector4& v,
156  ChartJacobian H = {}) {
157  return Similarity2::Expmap(v, H);
158  }
159  static Vector4 Local(const Similarity2& other,
160  ChartJacobian H = {}) {
161  return Similarity2::Logmap(other, H);
162  }
163  };
164 
166  Matrix4 AdjointMap() const;
167 
169 
173 
175  Matrix3 matrix() const;
176 
178  Rot2 rotation() const { return R_; }
179 
181  Point2 translation() const { return t_; }
182 
184  double scale() const { return s_; }
185 
187  inline static size_t Dim() { return 4; }
188 
190  inline size_t dim() const { return 4; }
191 
193 };
194 
195 template <>
196 struct traits<Similarity2> : public internal::LieGroup<Similarity2> {};
197 
198 template <>
199 struct traits<const Similarity2> : public internal::LieGroup<Similarity2> {};
200 
201 } // namespace gtsam
H
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
Definition: gnuplot_common_settings.hh:74
gtsam::Similarity2::Expmap
static Similarity2 Expmap(const Vector4 &v, OptionalJacobian< 4, 4 > Hm={})
Exponential map at the identity.
Definition: Similarity2.cpp:210
gtsam::Similarity2::dim
size_t dim() const
Dimensionality of tangent space = 4 DOF.
Definition: Similarity2.h:190
Pose2.h
2D Pose
inverse
const EIGEN_DEVICE_FUNC InverseReturnType inverse() const
Definition: ArrayCwiseUnaryOps.h:411
s
RealScalar s
Definition: level1_cplx_impl.h:126
gtsam::operator<<
std::ostream & operator<<(std::ostream &os, const Dih6 &m)
Definition: testGroup.cpp:109
gtsam::operator==
bool operator==(const Matrix &A, const Matrix &B)
Definition: base/Matrix.h:99
os
ofstream os("timeSchurFactors.csv")
gtsam::Similarity2::Rotation
Rot2 Rotation
Definition: Similarity2.h:38
gtsam::Similarity2::s_
double s_
Definition: Similarity2.h:45
Rot2.h
2D rotation
Point2.h
2D Point
gtsam::Similarity2::ChartAtOrigin::Retract
static Similarity2 Retract(const Vector4 &v, ChartJacobian H={})
Definition: Similarity2.h:155
gtsam::operator*
Point2 operator*(double s, const Point2 &p)
multiply with scalar
Definition: Point2.h:52
gtsam::Similarity2::t_
Point2 t_
Definition: Similarity2.h:44
Expmap
Pose2_ Expmap(const Vector3_ &xi)
Definition: InverseKinematicsExampleExpressions.cpp:47
gtsam::Similarity2::ChartAtOrigin
Chart at the origin.
Definition: Similarity2.h:154
gtsam::print
void print(const Matrix &A, const string &s, ostream &stream)
Definition: Matrix.cpp:155
gtsam::transformFrom
Point3_ transformFrom(const Pose3_ &x, const Point3_ &p)
Definition: slam/expressions.h:47
gtsam::Similarity2::ChartAtOrigin::Local
static Vector4 Local(const Similarity2 &other, ChartJacobian H={})
Definition: Similarity2.h:159
gtsam::internal::LieGroup
Both LieGroupTraits and Testable.
Definition: Lie.h:229
gtsam::Similarity2::Translation
Point2 Translation
Definition: Similarity2.h:39
Manifold.h
Base class and basic functions for Manifold types.
Vector2
Definition: test_operator_overloading.cpp:18
gtsam::Point2
Vector2 Point2
Definition: Point2.h:32
Eigen::Triplet< double >
gtsam::Similarity2
Definition: Similarity2.h:35
gtsam::equals
Definition: Testable.h:112
matrix
Map< Matrix< T, Dynamic, Dynamic, ColMajor >, 0, OuterStride<> > matrix(T *data, int rows, int cols, int stride)
Definition: gtsam/3rdparty/Eigen/blas/common.h:110
gtsam::Similarity2::rotation
Rot2 rotation() const
Return a GTSAM rotation.
Definition: Similarity2.h:178
gtsam::Rot2
Definition: Rot2.h:35
Lie.h
Base class and basic functions for Lie types.
gtsam
traits
Definition: SFMdata.h:40
gtsam::traits
Definition: Group.h:36
gtsam::OptionalJacobian
Definition: OptionalJacobian.h:38
gtsam::Similarity2::Logmap
static Vector4 Logmap(const Similarity2 &S, OptionalJacobian< 4, 4 > Hm={})
Definition: Similarity2.cpp:197
gtsam::Similarity2::scale
double scale() const
Return the scale.
Definition: Similarity2.h:184
p
float * p
Definition: Tutorial_Map_using.cpp:9
v
Array< int, Dynamic, 1 > v
Definition: Array_initializer_list_vector_cxx11.cpp:1
gtsam::LieGroup
Definition: Lie.h:37
gtsam::tol
const G double tol
Definition: Group.h:79
gtsam::Point2Pairs
std::vector< Point2Pair > Point2Pairs
Definition: Point2.h:38
gtsam::Similarity2::translation
Point2 translation() const
Return a GTSAM translation.
Definition: Similarity2.h:181
gtsam::Pose2Pairs
std::vector< Pose2Pair > Pose2Pairs
Definition: Pose2.h:362
gtsam::Similarity2::R_
Rot2 R_
Definition: Similarity2.h:43
gtsam::internal::Align
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
align_3::t
Point2 t(10, 10)
gtsam::Similarity2::Dim
static size_t Dim()
Dimensionality of tangent space = 4 DOF - used to autodetect sizes.
Definition: Similarity2.h:187
pybind_wrapper_test_script.other
other
Definition: pybind_wrapper_test_script.py:42
gtsam::LieGroup< Similarity2, 4 >::inverse
Similarity2 inverse(ChartJacobian H) const
Definition: Lie.h:71
R
Rot2 R(Rot2::fromAngle(0.1))
S
DiscreteKey S(1, 2)
gtsam::Pose2
Definition: Pose2.h:39


gtsam
Author(s):
autogenerated on Sat Nov 16 2024 04:04:12