GTSAM  4.0.2
C++ library for smoothing and mapping (SAM)
Pose2.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 // \callgraph
20 
21 #pragma once
22 
24 #include <gtsam/geometry/Point2.h>
25 #include <gtsam/geometry/Rot2.h>
26 #include <gtsam/base/Lie.h>
27 #include <gtsam/dllexport.h>
28 #include <gtsam/base/std_optional_serialization.h>
29 
30 #include <optional>
31 
32 namespace gtsam {
33 
39 class Pose2: public LieGroup<Pose2, 3> {
40 
41 public:
42 
44  typedef Rot2 Rotation;
45  typedef Point2 Translation;
46 
47 private:
48 
49  Rot2 r_;
50  Point2 t_;
51 
52 public:
53 
56 
58  Pose2() :
59  r_(traits<Rot2>::Identity()), t_(traits<Point2>::Identity()) {
60  }
61 
63  Pose2(const Pose2& pose) : r_(pose.r_), t_(pose.t_) {}
64 
71  Pose2(double x, double y, double theta) :
72  r_(Rot2::fromAngle(theta)), t_(x, y) {
73  }
74 
76  Pose2(double theta, const Point2& t) :
77  r_(Rot2::fromAngle(theta)), t_(t) {
78  }
79 
81  Pose2(const Rot2& r, const Point2& t) : r_(r), t_(t) {}
82 
84  Pose2(const Matrix &T) :
85  r_(Rot2::atan2(T(1, 0), T(0, 0))), t_(T(0, 2), T(1, 2)) {
86  assert(T.rows() == 3 && T.cols() == 3);
87  }
88 
92 
94  Pose2(const Vector& v) : Pose2() {
95  *this = Expmap(v);
96  }
97 
105  static std::optional<Pose2> Align(const Point2Pairs& abPointPairs);
106 
107  // Version of Pose2::Align that takes 2 matrices.
108  static std::optional<Pose2> Align(const Matrix& a, const Matrix& b);
109 
113 
115  GTSAM_EXPORT void print(const std::string& s = "") const;
116 
118  GTSAM_EXPORT bool equals(const Pose2& pose, double tol = 1e-9) const;
119 
123 
125  inline static Pose2 Identity() { return Pose2(); }
126 
128  GTSAM_EXPORT Pose2 inverse() const;
129 
131  inline Pose2 operator*(const Pose2& p2) const {
132  return Pose2(r_*p2.r(), t_ + r_*p2.t());
133  }
134 
138 
140  GTSAM_EXPORT static Pose2 Expmap(const Vector3& xi, ChartJacobian H = {});
141 
143  GTSAM_EXPORT static Vector3 Logmap(const Pose2& p, ChartJacobian H = {});
144 
149  GTSAM_EXPORT Matrix3 AdjointMap() const;
150 
152  inline Vector3 Adjoint(const Vector3& xi) const {
153  return AdjointMap()*xi;
154  }
155 
159  GTSAM_EXPORT static Matrix3 adjointMap(const Vector3& v);
160 
164  static Vector3 adjoint(const Vector3& xi, const Vector3& y) {
165  return adjointMap(xi) * y;
166  }
167 
171  static Vector3 adjointTranspose(const Vector3& xi, const Vector3& y) {
172  return adjointMap(xi).transpose() * y;
173  }
174 
175  // temporary fix for wrappers until case issue is resolved
176  static Matrix3 adjointMap_(const Vector3 &xi) { return adjointMap(xi);}
177  static Vector3 adjoint_(const Vector3 &xi, const Vector3 &y) { return adjoint(xi, y);}
178 
186  static inline Matrix3 wedge(double vx, double vy, double w) {
187  Matrix3 m;
188  m << 0.,-w, vx,
189  w, 0., vy,
190  0., 0., 0.;
191  return m;
192  }
193 
195  GTSAM_EXPORT static Matrix3 ExpmapDerivative(const Vector3& v);
196 
198  GTSAM_EXPORT static Matrix3 LogmapDerivative(const Pose2& v);
199 
200  // Chart at origin, depends on compile-time flag SLOW_BUT_CORRECT_EXPMAP
201  struct ChartAtOrigin {
202  GTSAM_EXPORT static Pose2 Retract(const Vector3& v, ChartJacobian H = {});
203  GTSAM_EXPORT static Vector3 Local(const Pose2& r, ChartJacobian H = {});
204  };
205 
206  using LieGroup<Pose2, 3>::inverse; // version with derivative
207 
211 
213  GTSAM_EXPORT Point2 transformTo(const Point2& point,
214  OptionalJacobian<2, 3> Dpose = {},
215  OptionalJacobian<2, 2> Dpoint = {}) const;
216 
222  Matrix transformTo(const Matrix& points) const;
223 
225  GTSAM_EXPORT Point2 transformFrom(const Point2& point,
226  OptionalJacobian<2, 3> Dpose = {},
227  OptionalJacobian<2, 2> Dpoint = {}) const;
228 
234  Matrix transformFrom(const Matrix& points) const;
235 
237  inline Point2 operator*(const Point2& point) const {
238  return transformFrom(point);
239  }
240 
244 
246  inline double x() const { return t_.x(); }
247 
249  inline double y() const { return t_.y(); }
250 
252  inline double theta() const { return r_.theta(); }
253 
255  inline const Point2& t() const { return t_; }
256 
258  inline const Rot2& r() const { return r_; }
259 
261  inline const Point2& translation() const { return t_; }
262 
264  inline const Rot2& rotation() const { return r_; }
265 
267  GTSAM_EXPORT Matrix3 matrix() const;
268 
274  GTSAM_EXPORT Rot2 bearing(const Point2& point,
276 
282  GTSAM_EXPORT Rot2 bearing(const Pose2& pose,
284 
290  GTSAM_EXPORT double range(const Point2& point,
292  OptionalJacobian<1, 2> H2={}) const;
293 
299  GTSAM_EXPORT double range(const Pose2& point,
301  OptionalJacobian<1, 3> H2={}) const;
302 
306 
312  inline static std::pair<size_t, size_t> translationInterval() { return {0, 1}; }
313 
319  static std::pair<size_t, size_t> rotationInterval() { return {2, 2}; }
320 
322  GTSAM_EXPORT
323  friend std::ostream &operator<<(std::ostream &os, const Pose2& p);
324 
326 
327  private:
328 
329 #ifdef GTSAM_ENABLE_BOOST_SERIALIZATION //
330  // Serialization function
331  friend class boost::serialization::access;
332  template<class Archive>
333  void serialize(Archive & ar, const unsigned int /*version*/) {
334  ar & BOOST_SERIALIZATION_NVP(t_);
335  ar & BOOST_SERIALIZATION_NVP(r_);
336  }
337 #endif
338 
339 public:
340  // Align for Point2, which is either derived from, or is typedef, of Vector2
342 }; // Pose2
343 
345 template <>
346 inline Matrix wedge<Pose2>(const Vector& xi) {
347  // NOTE(chris): Need eval() as workaround for Apple clang + avx2.
348  return Matrix(Pose2::wedge(xi(0),xi(1),xi(2))).eval();
349 }
350 
351 // Convenience typedef
352 using Pose2Pair = std::pair<Pose2, Pose2>;
353 using Pose2Pairs = std::vector<Pose2Pair>;
354 
355 template <>
356 struct traits<Pose2> : public internal::LieGroup<Pose2> {};
357 
358 template <>
359 struct traits<const Pose2> : public internal::LieGroup<Pose2> {};
360 
361 // bearing and range traits, used in RangeFactor
362 template <typename T>
363 struct Bearing<Pose2, T> : HasBearing<Pose2, T, Rot2> {};
364 
365 template <typename T>
366 struct Range<Pose2, T> : HasRange<Pose2, T, double> {};
367 
368 } // namespace gtsam
369 
GTSAM_EXPORT Point2 transformFrom(const Point2 &point, OptionalJacobian< 2, 3 > Dpose={}, OptionalJacobian< 2, 2 > Dpoint={}) const
GTSAM_EXPORT Matrix3 AdjointMap() const
Point2 operator*(const Point2 &point) const
Definition: Pose2.h:237
Pose2()
Definition: Pose2.h:58
Definition: Rot2.h:35
std::string serialize(const T &input)
serializes to a string
Definition: serialization.h:113
Definition: BearingRange.h:197
static Pose2 Identity()
identity for group operation
Definition: Pose2.h:125
Vector2 Point2
Definition: Point2.h:32
Definition: Group.h:43
Pose2(const Vector &v)
Definition: Pose2.h:94
Pose2(double x, double y, double theta)
Definition: Pose2.h:71
static Matrix3 wedge(double vx, double vy, double w)
Definition: Pose2.h:186
const Point2 & t() const
translation
Definition: Pose2.h:255
const Rot2 & rotation() const
rotation
Definition: Pose2.h:264
Definition: Lie.h:37
static std::pair< size_t, size_t > translationInterval()
Definition: Pose2.h:312
double y() const
get y
Definition: Pose2.h:249
Definition: BearingRange.h:183
Pose2(const Matrix &T)
Definition: Pose2.h:84
static GTSAM_EXPORT Matrix3 ExpmapDerivative(const Vector3 &v)
Derivative of Expmap.
GTSAM_EXPORT void print(const std::string &s="") const
Definition: Pose2.h:39
Pose2(const Pose2 &pose)
Definition: Pose2.h:63
const Rot2 & r() const
rotation
Definition: Pose2.h:258
double theta() const
get theta
Definition: Pose2.h:252
Matrix wedge< Pose2 >(const Vector &xi)
Definition: Pose2.h:346
static GTSAM_EXPORT Pose2 Expmap(const Vector3 &xi, ChartJacobian H={})
Exponential map at identity - create a rotation from canonical coordinates .
Definition: Pose2.h:201
Definition: BearingRange.h:35
Pose2(const Rot2 &r, const Point2 &t)
Definition: Pose2.h:81
Pose2 operator*(const Pose2 &p2) const
compose syntactic sugar
Definition: Pose2.h:131
Base class and basic functions for Lie types.
Definition: BearingRange.h:41
Definition: chartTesting.h:28
static std::pair< size_t, size_t > rotationInterval()
Definition: Pose2.h:319
Vector3 Adjoint(const Vector3 &xi) const
Apply AdjointMap to twist xi.
Definition: Pose2.h:152
GTSAM_EXPORT Pose2 inverse() const
inverse
static Vector3 adjointTranspose(const Vector3 &xi, const Vector3 &y)
Definition: Pose2.h:171
GTSAM_EXPORT Rot2 bearing(const Point2 &point, OptionalJacobian< 1, 3 > H1={}, OptionalJacobian< 1, 2 > H2={}) const
static GTSAM_EXPORT Matrix3 LogmapDerivative(const Pose2 &v)
Derivative of Logmap.
Definition: OptionalJacobian.h:38
Both LieGroupTraits and Testable.
Definition: Lie.h:229
Bearing-Range product.
GTSAM_EXPORT Point2 transformTo(const Point2 &point, OptionalJacobian< 2, 3 > Dpose={}, OptionalJacobian< 2, 2 > Dpoint={}) const
static GTSAM_EXPORT Vector3 Logmap(const Pose2 &p, ChartJacobian H={})
Log map at identity - return the canonical coordinates of this rotation.
static GTSAM_EXPORT Matrix3 adjointMap(const Vector3 &v)
Pose2(double theta, const Point2 &t)
Definition: Pose2.h:76
#define GTSAM_MAKE_ALIGNED_OPERATOR_NEW
Definition: types.h:284
GTSAM_EXPORT friend std::ostream & operator<<(std::ostream &os, const Pose2 &p)
Output stream operator.
const Point2 & translation() const
translation
Definition: Pose2.h:261
GTSAM_EXPORT bool equals(const Pose2 &pose, double tol=1e-9) const
GTSAM_EXPORT double range(const Point2 &point, OptionalJacobian< 1, 3 > H1={}, OptionalJacobian< 1, 2 > H2={}) const
2D Point
double x() const
get x
Definition: Pose2.h:246
static Vector3 adjoint(const Vector3 &xi, const Vector3 &y)
Definition: Pose2.h:164
Rot2 Rotation
Definition: Pose2.h:44
static std::optional< Pose2 > Align(const Point2Pairs &abPointPairs)
2D rotation
double theta() const
Definition: Rot2.h:186