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  using Rotation = Rot2;
46 
48  using LieAlgebra = Matrix3;
49 
50 private:
51 
54 
55 public:
56 
59 
61  Pose2() :
62  r_(traits<Rot2>::Identity()), t_(traits<Point2>::Identity()) {
63  }
64 
66  Pose2(const Pose2& pose) = default;
67  // : r_(pose.r_), t_(pose.t_) {}
68 
69  Pose2& operator=(const Pose2& other) = default;
70 
77  Pose2(double x, double y, double theta) :
78  r_(Rot2::fromAngle(theta)), t_(x, y) {
79  }
80 
82  Pose2(double theta, const Point2& t) :
83  r_(Rot2::fromAngle(theta)), t_(t) {
84  }
85 
87  Pose2(const Rot2& r, const Point2& t) : r_(r), t_(t) {}
88 
90  Pose2(const Matrix &T)
91  : r_(Rot2::atan2(T(1, 0), T(0, 0))), t_(T(0, 2), T(1, 2)) {
92 #ifndef NDEBUG
93  if (T.rows() != 3 || T.cols() != 3) {
94  throw;
95  }
96 #endif
97  }
98 
102 
104  Pose2(const Vector& v) : Pose2() {
105  *this = Expmap(v);
106  }
107 
115  static std::optional<Pose2> Align(const Point2Pairs& abPointPairs);
116 
117  // Version of Pose2::Align that takes 2 matrices.
118  static std::optional<Pose2> Align(const Matrix& a, const Matrix& b);
119 
123 
125  void print(const std::string& s = "") const;
126 
128  bool equals(const Pose2& pose, double tol = 1e-9) const;
129 
133 
135  inline static Pose2 Identity() { return Pose2(); }
136 
138  Pose2 inverse() const;
139 
141  inline Pose2 operator*(const Pose2& p2) const {
142  return Pose2(r_*p2.r(), t_ + r_*p2.t());
143  }
144 
148 
150  static Pose2 Expmap(const Vector3& xi, ChartJacobian H = {});
151 
153  static Vector3 Logmap(const Pose2& p, ChartJacobian H = {});
154 
159  Matrix3 AdjointMap() const;
160 
162  inline Vector3 Adjoint(const Vector3& xi) const {
163  return AdjointMap()*xi;
164  }
165 
169  static Matrix3 adjointMap(const Vector3& v);
170 
174  static Vector3 adjoint(const Vector3& xi, const Vector3& y) {
175  return adjointMap(xi) * y;
176  }
177 
181  static Vector3 adjointTranspose(const Vector3& xi, const Vector3& y) {
182  return adjointMap(xi).transpose() * y;
183  }
184 
185  // temporary fix for wrappers until case issue is resolved
186  static Matrix3 adjointMap_(const Vector3 &xi) { return adjointMap(xi);}
187  static Vector3 adjoint_(const Vector3 &xi, const Vector3 &y) { return adjoint(xi, y);}
188 
190  static Matrix3 ExpmapDerivative(const Vector3& v);
191 
193  static Matrix3 LogmapDerivative(const Pose2& v);
194 
195  // Chart at origin, depends on compile-time flag SLOW_BUT_CORRECT_EXPMAP
196  struct GTSAM_EXPORT ChartAtOrigin {
197  static Pose2 Retract(const Vector3& v, ChartJacobian H = {});
198  static Vector3 Local(const Pose2& r, ChartJacobian H = {});
199  };
200 
201  using LieGroup<Pose2, 3>::inverse; // version with derivative
202 
204  static Matrix3 Hat(const Vector3& xi);
205 
207  static Vector3 Vee(const Matrix3& X);
208 
212 
215  OptionalJacobian<2, 3> Dpose = {},
216  OptionalJacobian<2, 2> Dpoint = {}) const;
217 
223  Matrix transformTo(const Matrix& points) const;
224 
227  OptionalJacobian<2, 3> Dpose = {},
228  OptionalJacobian<2, 2> Dpoint = {}) const;
229 
235  Matrix transformFrom(const Matrix& points) const;
236 
238  inline Point2 operator*(const Point2& point) const {
239  return transformFrom(point);
240  }
241 
245 
247  inline double x() const { return t_.x(); }
248 
250  inline double y() const { return t_.y(); }
251 
253  inline double theta() const { return r_.theta(); }
254 
256  inline const Point2& t() const { return t_; }
257 
259  inline const Rot2& r() const { return r_; }
260 
262  inline const Point2& translation(OptionalJacobian<2, 3> Hself={}) const {
263  if (Hself) {
264  *Hself = Matrix::Zero(2, 3);
265  (*Hself).block<2, 2>(0, 0) = rotation().matrix();
266  }
267  return t_;
268  }
269 
271  inline const Rot2& rotation(OptionalJacobian<1, 3> Hself={}) const {
272  if (Hself) *Hself << 0, 0, 1;
273  return r_;
274  }
275 
277  Matrix3 matrix() const;
278 
284  Rot2 bearing(const Point2& point,
285  OptionalJacobian<1, 3> H1={}, OptionalJacobian<1, 2> H2={}) const;
286 
292  Rot2 bearing(const Pose2& pose,
293  OptionalJacobian<1, 3> H1={}, OptionalJacobian<1, 3> H2={}) const;
294 
300  double range(const Point2& point,
301  OptionalJacobian<1, 3> H1={},
302  OptionalJacobian<1, 2> H2={}) const;
303 
309  double range(const Pose2& point,
310  OptionalJacobian<1, 3> H1={},
311  OptionalJacobian<1, 3> H2={}) const;
312 
316 
322  inline static std::pair<size_t, size_t> translationInterval() { return {0, 1}; }
323 
329  static std::pair<size_t, size_t> rotationInterval() { return {2, 2}; }
330 
332  Vector9 vec(OptionalJacobian<9, 3> H = {}) const;
333 
335  GTSAM_EXPORT
336  friend std::ostream &operator<<(std::ostream &os, const Pose2& p);
337 
341 
342 #ifdef GTSAM_ALLOW_DEPRECATED_SINCE_V43
343  static inline Matrix3 wedge(double vx, double vy, double w) {
345  return Hat(TangentVector(vx, vy, w));
346  }
347 #endif
348 
350  private:
351 
352 #if GTSAM_ENABLE_BOOST_SERIALIZATION //
353  // Serialization function
354  friend class boost::serialization::access;
355  template<class Archive>
356  void serialize(Archive & ar, const unsigned int /*version*/) {
357  ar & BOOST_SERIALIZATION_NVP(t_);
358  ar & BOOST_SERIALIZATION_NVP(r_);
359  }
360 #endif
361 
362 public:
363  // Align for Point2, which is either derived from, or is typedef, of Vector2
365 }; // Pose2
366 
367 #ifdef GTSAM_ALLOW_DEPRECATED_SINCE_V43
368 template <>
370 inline Matrix wedge<Pose2>(const Vector& xi) {
371  // NOTE(chris): Need eval() as workaround for Apple clang + avx2.
372  return Matrix(Pose2::Hat(xi)).eval();
373 }
374 #endif
375 
376 // Convenience typedef
377 using Pose2Pair = std::pair<Pose2, Pose2>;
378 using Pose2Pairs = std::vector<Pose2Pair>;
379 
380 template <>
381 struct traits<Pose2> : public internal::MatrixLieGroup<Pose2> {};
382 
383 template <>
384 struct traits<const Pose2> : public internal::MatrixLieGroup<Pose2> {};
385 
386 // bearing and range traits, used in RangeFactor
387 template <typename T>
388 struct Bearing<Pose2, T> : HasBearing<Pose2, T, Rot2> {};
389 
390 template <typename T>
391 struct Range<Pose2, T> : HasRange<Pose2, T, double> {};
392 
393 } // namespace gtsam
394 
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::Translation
Point2 Translation
Definition: Pose2.h:45
gtsam::Pose2::Pose2
Pose2(const Matrix &T)
Definition: Pose2.h:90
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:187
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:162
gtsam::operator<<
std::ostream & operator<<(std::ostream &os, const Dih6 &m)
Definition: testGroup.cpp:109
screwPose2::xi
Vector xi
Definition: testPose2.cpp:169
gtsam::Pose2::adjointMap_
static Matrix3 adjointMap_(const Vector3 &xi)
Definition: Pose2.h:186
gtsam::Pose2::rotation
const Rot2 & rotation(OptionalJacobian< 1, 3 > Hself={}) const
rotation
Definition: Pose2.h:271
gtsam::Pose2::t
const Point2 & t() const
translation
Definition: Pose2.h:256
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:197
gtsam::Matrix
Eigen::MatrixXd Matrix
Definition: base/Matrix.h:39
X
#define X
Definition: icosphere.cpp:20
gtsam::Vector3
Eigen::Vector3d Vector3
Definition: Vector.h:44
os
ofstream os("timeSchurFactors.csv")
gtsam::Vector
Eigen::VectorXd Vector
Definition: Vector.h:39
Rot2.h
2D rotation
Point2.h
2D Point
gtsam::Pose2::translationInterval
static std::pair< size_t, size_t > translationInterval()
Definition: Pose2.h:322
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:183
gtsam::print
void print(const Matrix &A, const string &s, ostream &stream)
Definition: Matrix.cpp:145
gtsam::Pose2::operator*
Pose2 operator*(const Pose2 &p2) const
compose syntactic sugar
Definition: Pose2.h:141
gtsam::transformFrom
Point3_ transformFrom(const Pose3_ &x, const Point3_ &p)
Definition: slam/expressions.h:47
gtsam::Pose2::ChartAtOrigin
Definition: Pose2.h:196
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::MatrixLieGroup
Both LieGroupTraits and Testable.
Definition: Lie.h:247
gtsam::Pose2::LieAlgebra
Matrix3 LieAlgebra
LieGroup Concept requirements.
Definition: Pose2.h:48
gtsam::Pose2::r
const Rot2 & r() const
rotation
Definition: Pose2.h:259
gtsam::Pose2::Identity
static Pose2 Identity()
identity for group operation
Definition: Pose2.h:135
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:104
gtsam::equals
Definition: Testable.h:112
gtsam::Pose2::Pose2
Pose2(const Rot2 &r, const Point2 &t)
Definition: Pose2.h:87
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:253
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:181
gtsam::Pose2::Pose2
Pose2()
Definition: Pose2.h:61
gtsam::Pose2::translation
const Point2 & translation(OptionalJacobian< 2, 3 > Hself={}) const
translation
Definition: Pose2.h:262
Lie.h
Base class and basic functions for Lie types.
gtsam::Pose2::Pose2
Pose2(double theta, const Point2 &t)
Definition: Pose2.h:82
gtsam
traits
Definition: SFMdata.h:40
gtsam::rotation
Rot3_ rotation(const Pose3_ &pose)
Definition: slam/expressions.h:93
gtsam::traits
Definition: Group.h:36
gtsam::OptionalJacobian
Definition: OptionalJacobian.h:38
gtsam::Pose2::x
double x() const
get x
Definition: Pose2.h:247
gtsam::Pose2::r_
Rot2 r_
Definition: Pose2.h:52
gtsam::HasRange
Definition: BearingRange.h:197
p
float * p
Definition: Tutorial_Map_using.cpp:9
gtsam::Pose2::rotationInterval
static std::pair< size_t, size_t > rotationInterval()
Definition: Pose2.h:329
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:77
gtsam::Pose2::adjoint
static Vector3 adjoint(const Vector3 &xi, const Vector3 &y)
Definition: Pose2.h:174
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:378
gtsam::Pose2::operator*
Point2 operator*(const Point2 &point) const
Definition: Pose2.h:238
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
pybind_wrapper_test_script.other
other
Definition: pybind_wrapper_test_script.py:42
gtsam::Pose2::y
double y() const
get y
Definition: Pose2.h:250
gtsam::Pose2::t_
Point2 t_
Definition: Pose2.h:53
gtsam::Pose2Pair
std::pair< Pose2, Pose2 > Pose2Pair
Definition: Pose2.h:377
vx
StridedVectorType vx(make_vector(x, *n, std::abs(*incx)))
gtsam::Pose2
Definition: Pose2.h:39
gtsam::Pose2::Hat
static Matrix3 Hat(const Vector3 &xi)
Hat maps from tangent vector to Lie algebra.
Definition: Pose2.cpp:207


gtsam
Author(s):
autogenerated on Wed Mar 19 2025 03:02:56