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>
29 
30 #include <optional>
31 
32 namespace gtsam {
33 
39 class GTSAM_EXPORT Pose2: public LieGroup<Pose2, 3> {
40 
41 public:
42 
44  typedef Rot2 Rotation;
46 
47 private:
48 
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 #ifndef NDEBUG
87  if (T.rows() != 3 || T.cols() != 3) {
88  throw;
89  }
90 #endif
91  }
92 
96 
98  Pose2(const Vector& v) : Pose2() {
99  *this = Expmap(v);
100  }
101 
109  static std::optional<Pose2> Align(const Point2Pairs& abPointPairs);
110 
111  // Version of Pose2::Align that takes 2 matrices.
112  static std::optional<Pose2> Align(const Matrix& a, const Matrix& b);
113 
117 
119  void print(const std::string& s = "") const;
120 
122  bool equals(const Pose2& pose, double tol = 1e-9) const;
123 
127 
129  inline static Pose2 Identity() { return Pose2(); }
130 
132  Pose2 inverse() const;
133 
135  inline Pose2 operator*(const Pose2& p2) const {
136  return Pose2(r_*p2.r(), t_ + r_*p2.t());
137  }
138 
142 
144  static Pose2 Expmap(const Vector3& xi, ChartJacobian H = {});
145 
147  static Vector3 Logmap(const Pose2& p, ChartJacobian H = {});
148 
153  Matrix3 AdjointMap() const;
154 
156  inline Vector3 Adjoint(const Vector3& xi) const {
157  return AdjointMap()*xi;
158  }
159 
163  static Matrix3 adjointMap(const Vector3& v);
164 
168  static Vector3 adjoint(const Vector3& xi, const Vector3& y) {
169  return adjointMap(xi) * y;
170  }
171 
175  static Vector3 adjointTranspose(const Vector3& xi, const Vector3& y) {
176  return adjointMap(xi).transpose() * y;
177  }
178 
179  // temporary fix for wrappers until case issue is resolved
180  static Matrix3 adjointMap_(const Vector3 &xi) { return adjointMap(xi);}
181  static Vector3 adjoint_(const Vector3 &xi, const Vector3 &y) { return adjoint(xi, y);}
182 
190  static inline Matrix3 wedge(double vx, double vy, double w) {
191  Matrix3 m;
192  m << 0.,-w, vx,
193  w, 0., vy,
194  0., 0., 0.;
195  return m;
196  }
197 
199  static Matrix3 ExpmapDerivative(const Vector3& v);
200 
202  static Matrix3 LogmapDerivative(const Pose2& v);
203 
204  // Chart at origin, depends on compile-time flag SLOW_BUT_CORRECT_EXPMAP
205  struct GTSAM_EXPORT ChartAtOrigin {
206  static Pose2 Retract(const Vector3& v, ChartJacobian H = {});
207  static Vector3 Local(const Pose2& r, ChartJacobian H = {});
208  };
209 
210  using LieGroup<Pose2, 3>::inverse; // version with derivative
211 
215 
218  OptionalJacobian<2, 3> Dpose = {},
219  OptionalJacobian<2, 2> Dpoint = {}) const;
220 
226  Matrix transformTo(const Matrix& points) const;
227 
230  OptionalJacobian<2, 3> Dpose = {},
231  OptionalJacobian<2, 2> Dpoint = {}) const;
232 
238  Matrix transformFrom(const Matrix& points) const;
239 
241  inline Point2 operator*(const Point2& point) const {
242  return transformFrom(point);
243  }
244 
248 
250  inline double x() const { return t_.x(); }
251 
253  inline double y() const { return t_.y(); }
254 
256  inline double theta() const { return r_.theta(); }
257 
259  inline const Point2& t() const { return t_; }
260 
262  inline const Rot2& r() const { return r_; }
263 
265  inline const Point2& translation(OptionalJacobian<2, 3> Hself={}) const {
266  if (Hself) {
267  *Hself = Matrix::Zero(2, 3);
268  (*Hself).block<2, 2>(0, 0) = rotation().matrix();
269  }
270  return t_;
271  }
272 
274  inline const Rot2& rotation(OptionalJacobian<1, 3> Hself={}) const {
275  if (Hself) *Hself << 0, 0, 1;
276  return r_;
277  }
278 
280  Matrix3 matrix() const;
281 
287  Rot2 bearing(const Point2& point,
288  OptionalJacobian<1, 3> H1={}, OptionalJacobian<1, 2> H2={}) const;
289 
295  Rot2 bearing(const Pose2& pose,
296  OptionalJacobian<1, 3> H1={}, OptionalJacobian<1, 3> H2={}) const;
297 
303  double range(const Point2& point,
304  OptionalJacobian<1, 3> H1={},
305  OptionalJacobian<1, 2> H2={}) const;
306 
312  double range(const Pose2& point,
313  OptionalJacobian<1, 3> H1={},
314  OptionalJacobian<1, 3> H2={}) const;
315 
319 
325  inline static std::pair<size_t, size_t> translationInterval() { return {0, 1}; }
326 
332  static std::pair<size_t, size_t> rotationInterval() { return {2, 2}; }
333 
335  GTSAM_EXPORT
336  friend std::ostream &operator<<(std::ostream &os, const Pose2& p);
337 
339 
340  private:
341 
342 #ifdef GTSAM_ENABLE_BOOST_SERIALIZATION //
343  // Serialization function
344  friend class boost::serialization::access;
345  template<class Archive>
346  void serialize(Archive & ar, const unsigned int /*version*/) {
347  ar & BOOST_SERIALIZATION_NVP(t_);
348  ar & BOOST_SERIALIZATION_NVP(r_);
349  }
350 #endif
351 
352 public:
353  // Align for Point2, which is either derived from, or is typedef, of Vector2
355 }; // Pose2
356 
358 template <>
359 inline Matrix wedge<Pose2>(const Vector& xi) {
360  // NOTE(chris): Need eval() as workaround for Apple clang + avx2.
361  return Matrix(Pose2::wedge(xi(0),xi(1),xi(2))).eval();
362 }
363 
364 // Convenience typedef
365 using Pose2Pair = std::pair<Pose2, Pose2>;
366 using Pose2Pairs = std::vector<Pose2Pair>;
367 
368 template <>
369 struct traits<Pose2> : public internal::LieGroup<Pose2> {};
370 
371 template <>
372 struct traits<const Pose2> : public internal::LieGroup<Pose2> {};
373 
374 // bearing and range traits, used in RangeFactor
375 template <typename T>
376 struct Bearing<Pose2, T> : HasBearing<Pose2, T, Rot2> {};
377 
378 template <typename T>
379 struct Range<Pose2, T> : HasRange<Pose2, T, double> {};
380 
381 } // namespace gtsam
382 
w
RowVector3d w
Definition: Matrix_resize_int.cpp:3
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::Pose2::Rotation
Rot2 Rotation
Definition: Pose2.h:44
gtsam::Pose2::Pose2
Pose2(const Matrix &T)
Definition: Pose2.h:84
pose
static const Pose3 pose(Rot3(Vector3(1, -1, -1).asDiagonal()), Point3(0, 0, 0.5))
inverse
const EIGEN_DEVICE_FUNC InverseReturnType inverse() const
Definition: ArrayCwiseUnaryOps.h:411
gtsam::Pose2::adjoint_
static Vector3 adjoint_(const Vector3 &xi, const Vector3 &y)
Definition: Pose2.h:181
s
RealScalar s
Definition: level1_cplx_impl.h:126
e
Array< double, 1, 3 > e(1./3., 0.5, 2.)
gtsam::Pose2::Adjoint
Vector3 Adjoint(const Vector3 &xi) const
Apply AdjointMap to twist xi.
Definition: Pose2.h:156
gtsam::operator<<
std::ostream & operator<<(std::ostream &os, const Dih6 &m)
Definition: testGroup.cpp:109
screwPose2::xi
Vector xi
Definition: testPose2.cpp:148
gtsam::Pose2::adjointMap_
static Matrix3 adjointMap_(const Vector3 &xi)
Definition: Pose2.h:180
gtsam::Pose2::rotation
const Rot2 & rotation(OptionalJacobian< 1, 3 > Hself={}) const
rotation
Definition: Pose2.h:274
gtsam::Pose2::t
const Point2 & t() const
translation
Definition: Pose2.h:259
x
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 x
Definition: gnuplot_common_settings.hh:12
gtsam::Rot2::theta
double theta() const
Definition: Rot2.h:186
gtsam::Matrix
Eigen::MatrixXd Matrix
Definition: base/Matrix.h:39
gtsam::Vector3
Eigen::Vector3d Vector3
Definition: Vector.h:44
os
ofstream os("timeSchurFactors.csv")
gtsam::Vector
Eigen::VectorXd Vector
Definition: Vector.h:39
gtsam::Pose2::Translation
Point2 Translation
Definition: Pose2.h:45
Rot2.h
2D rotation
Point2.h
2D Point
gtsam::Pose2::translationInterval
static std::pair< size_t, size_t > translationInterval()
Definition: Pose2.h:325
gtsam::range
Double_ range(const Point2_ &p, const Point2_ &q)
Definition: slam/expressions.h:30
simple::p2
static Point3 p2
Definition: testInitializePose3.cpp:51
gtsam_unstable.tests.test_ProjectionFactorRollingShutter.point
point
Definition: test_ProjectionFactorRollingShutter.py:25
Expmap
Pose2_ Expmap(const Vector3_ &xi)
Definition: InverseKinematicsExampleExpressions.cpp:47
gtsam::HasBearing
Definition: BearingRange.h:181
gtsam::print
void print(const Matrix &A, const string &s, ostream &stream)
Definition: Matrix.cpp:156
gtsam::Pose2::operator*
Pose2 operator*(const Pose2 &p2) const
compose syntactic sugar
Definition: Pose2.h:135
gtsam::transformFrom
Point3_ transformFrom(const Pose3_ &x, const Point3_ &p)
Definition: slam/expressions.h:47
gtsam::Pose2::ChartAtOrigin
Definition: Pose2.h:205
vy
StridedVectorType vy(make_vector(y, *n, std::abs(*incy)))
gtsam::transformTo
Line3 transformTo(const Pose3 &wTc, const Line3 &wL, OptionalJacobian< 4, 6 > Dpose, OptionalJacobian< 4, 4 > Dline)
Definition: Line3.cpp:94
gtsam::internal::LieGroup
Both LieGroupTraits and Testable.
Definition: Lie.h:229
gtsam::Pose2::Pose2
Pose2(const Pose2 &pose)
Definition: Pose2.h:63
gtsam::Pose2::r
const Rot2 & r() const
rotation
Definition: Pose2.h:262
gtsam::Pose2::Identity
static Pose2 Identity()
identity for group operation
Definition: Pose2.h:129
m
Matrix3f m
Definition: AngleAxis_mimic_euler.cpp:1
gtsam::Point2
Vector2 Point2
Definition: Point2.h:32
Eigen::Triplet< double >
gtsam::Range
Definition: BearingRange.h:41
gtsam::Pose2::Pose2
Pose2(const Vector &v)
Definition: Pose2.h:98
gtsam::equals
Definition: Testable.h:112
gtsam::Pose2::Pose2
Pose2(const Rot2 &r, const Point2 &t)
Definition: Pose2.h:81
y
Scalar * y
Definition: level1_cplx_impl.h:124
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::Pose2::theta
double theta() const
get theta
Definition: Pose2.h:256
std_optional_serialization.h
atan2
AnnoyingScalar atan2(const AnnoyingScalar &y, const AnnoyingScalar &x)
Definition: AnnoyingScalar.h:110
gtsam::b
const G & b
Definition: Group.h:79
gtsam::Rot2
Definition: Rot2.h:35
a
ArrayXXi a
Definition: Array_initializer_list_23_cxx11.cpp:1
gtsam::Pose2::adjointTranspose
static Vector3 adjointTranspose(const Vector3 &xi, const Vector3 &y)
Definition: Pose2.h:175
gtsam::Pose2::Pose2
Pose2()
Definition: Pose2.h:58
gtsam::Pose2::translation
const Point2 & translation(OptionalJacobian< 2, 3 > Hself={}) const
translation
Definition: Pose2.h:265
Lie.h
Base class and basic functions for Lie types.
gtsam::Pose2::Pose2
Pose2(double theta, const Point2 &t)
Definition: Pose2.h:76
gtsam
traits
Definition: SFMdata.h:40
gtsam::rotation
Rot3_ rotation(const Pose3_ &pose)
Definition: slam/expressions.h:89
gtsam::traits
Definition: Group.h:36
gtsam::OptionalJacobian
Definition: OptionalJacobian.h:38
gtsam::Pose2::x
double x() const
get x
Definition: Pose2.h:250
gtsam::Pose2::r_
Rot2 r_
Definition: Pose2.h:49
gtsam::HasRange
Definition: BearingRange.h:195
p
float * p
Definition: Tutorial_Map_using.cpp:9
gtsam::Pose2::rotationInterval
static std::pair< size_t, size_t > rotationInterval()
Definition: Pose2.h:332
v
Array< int, Dynamic, 1 > v
Definition: Array_initializer_list_vector_cxx11.cpp:1
gtsam::Pose2::Pose2
Pose2(double x, double y, double theta)
Definition: Pose2.h:71
gtsam::Pose2::adjoint
static Vector3 adjoint(const Vector3 &xi, const Vector3 &y)
Definition: Pose2.h:168
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::Pose2Pairs
std::vector< Pose2Pair > Pose2Pairs
Definition: Pose2.h:366
gtsam::Pose2::operator*
Point2 operator*(const Point2 &point) const
Definition: Pose2.h:241
gtsam::Pose2::wedge
static Matrix3 wedge(double vx, double vy, double w)
Definition: Pose2.h:190
BearingRange.h
Bearing-Range product.
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
gtsam::Bearing
Definition: BearingRange.h:35
align_3::t
Point2 t(10, 10)
GTSAM_MAKE_ALIGNED_OPERATOR_NEW
#define GTSAM_MAKE_ALIGNED_OPERATOR_NEW
Definition: types.h:279
adjoint
void adjoint(const MatrixType &m)
Definition: adjoint.cpp:67
gtsam::wedge< Pose2 >
Matrix wedge< Pose2 >(const Vector &xi)
Definition: Pose2.h:359
gtsam::Pose2::y
double y() const
get y
Definition: Pose2.h:253
gtsam::Pose2::t_
Point2 t_
Definition: Pose2.h:50
gtsam::Pose2Pair
std::pair< Pose2, Pose2 > Pose2Pair
Definition: Pose2.h:365
vx
StridedVectorType vx(make_vector(x, *n, std::abs(*incx)))
gtsam::Pose2
Definition: Pose2.h:39


gtsam
Author(s):
autogenerated on Sun Dec 22 2024 04:12:45