Pose3.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 
17 // \callgraph
18 #pragma once
19 
20 #include <gtsam/config.h>
21 
23 #include <gtsam/geometry/Point3.h>
24 #include <gtsam/geometry/Rot3.h>
25 #include <gtsam/base/Lie.h>
26 
27 namespace gtsam {
28 
29 class Pose2;
30 // forward declare
31 
37 class GTSAM_EXPORT Pose3: public LieGroup<Pose3, 6> {
38 public:
39 
41  typedef Rot3 Rotation;
43 
44 private:
45 
46  Rot3 R_;
48 
49 public:
50 
53 
55  Pose3() : R_(traits<Rot3>::Identity()), t_(traits<Point3>::Identity()) {}
56 
58  Pose3(const Pose3& pose) = default;
59 
60  Pose3& operator=(const Pose3& other) = default;
61 
63  Pose3(const Rot3& R, const Point3& t) :
64  R_(R), t_(t) {
65  }
66 
68  explicit Pose3(const Pose2& pose2);
69 
71  Pose3(const Matrix &T) :
72  R_(T(0, 0), T(0, 1), T(0, 2), T(1, 0), T(1, 1), T(1, 2), T(2, 0), T(2, 1),
73  T(2, 2)), t_(T(0, 3), T(1, 3), T(2, 3)) {
74  }
75 
77  static Pose3 Create(const Rot3& R, const Point3& t,
79  OptionalJacobian<6, 3> Ht = {});
80 
82  static Pose3 FromPose2(const Pose2& p, OptionalJacobian<6,3> H = {});
83 
89  static std::optional<Pose3> Align(const Point3Pairs& abPointPairs);
90 
91  // Version of Pose3::Align that takes 2 matrices.
92  static std::optional<Pose3> Align(const Matrix& a, const Matrix& b);
93 
97 
99  void print(const std::string& s = "") const;
100 
102  bool equals(const Pose3& pose, double tol = 1e-9) const;
103 
107 
109  static Pose3 Identity() {
110  return Pose3();
111  }
112 
114  Pose3 inverse() const;
115 
117  Pose3 operator*(const Pose3& T) const {
118  return Pose3(R_ * T.R_, t_ + R_ * T.t_);
119  }
120 
135  Pose3 interpolateRt(const Pose3& T, double t,
136  OptionalJacobian<6, 6> Hself = {},
137  OptionalJacobian<6, 6> Harg = {},
138  OptionalJacobian<6, 1> Ht = {}) const;
139 
143 
144  using LieAlgebra = Matrix4;
145 
147  static Pose3 Expmap(const Vector6& xi, OptionalJacobian<6, 6> Hxi = {});
148 
150  static Vector6 Logmap(const Pose3& pose, OptionalJacobian<6, 6> Hpose = {});
151 
156  Matrix6 AdjointMap() const;
157 
164  Vector6 Adjoint(const Vector6& xi_b,
165  OptionalJacobian<6, 6> H_this = {},
166  OptionalJacobian<6, 6> H_xib = {}) const;
167 
169  Vector6 AdjointTranspose(const Vector6& x,
170  OptionalJacobian<6, 6> H_this = {},
171  OptionalJacobian<6, 6> H_x = {}) const;
172 
188  static Matrix6 adjointMap(const Vector6& xi);
189 
193  static Vector6 adjoint(const Vector6& xi, const Vector6& y,
194  OptionalJacobian<6, 6> Hxi = {},
195  OptionalJacobian<6, 6> H_y = {});
196 
197  // temporary fix for wrappers until case issue is resolved
198  static Matrix6 adjointMap_(const Vector6 &xi) { return adjointMap(xi);}
199  static Vector6 adjoint_(const Vector6 &xi, const Vector6 &y) { return adjoint(xi, y);}
200 
204  static Vector6 adjointTranspose(const Vector6& xi, const Vector6& y,
205  OptionalJacobian<6, 6> Hxi = {},
206  OptionalJacobian<6, 6> H_y = {});
207 
209  static Matrix6 ExpmapDerivative(const Vector6& xi);
210 
212  static Matrix6 LogmapDerivative(const Vector6& xi);
213 
215  static Matrix6 LogmapDerivative(const Pose3& pose);
216 
217  // Chart at origin, depends on compile-time flag GTSAM_POSE3_EXPMAP
218  struct GTSAM_EXPORT ChartAtOrigin {
219  static Pose3 Retract(const Vector6& xi, ChartJacobian Hxi = {});
220  static Vector6 Local(const Pose3& pose, ChartJacobian Hpose = {});
221  };
222 
223  using LieGroup<Pose3, 6>::inverse; // version with derivative
224 
232  static Matrix4 Hat(const Vector6& xi);
233 
235  static Vector6 Vee(const Matrix4& X);
236 
240 
249  {}, OptionalJacobian<3, 3> Hpoint = {}) const;
250 
256  Matrix transformFrom(const Matrix& points) const;
257 
259  inline Point3 operator*(const Point3& point) const {
260  return transformFrom(point);
261  }
262 
271  {}, OptionalJacobian<3, 3> Hpoint = {}) const;
272 
278  Matrix transformTo(const Matrix& points) const;
279 
283 
285  const Rot3& rotation(OptionalJacobian<3, 6> Hself = {}) const;
286 
288  const Point3& translation(OptionalJacobian<3, 6> Hself = {}) const;
289 
291  double x() const {
292  return t_.x();
293  }
294 
296  double y() const {
297  return t_.y();
298  }
299 
301  double z() const {
302  return t_.z();
303  }
304 
306  Matrix4 matrix() const;
307 
313  Pose3 transformPoseFrom(const Pose3& aTb, OptionalJacobian<6, 6> Hself = {},
314  OptionalJacobian<6, 6> HaTb = {}) const;
315 
320  Pose3 transformPoseTo(const Pose3& wTb, OptionalJacobian<6, 6> Hself = {},
321  OptionalJacobian<6, 6> HwTb = {}) const;
322 
328  double range(const Point3& point, OptionalJacobian<1, 6> Hself = {},
329  OptionalJacobian<1, 3> Hpoint = {}) const;
330 
336  double range(const Pose3& pose, OptionalJacobian<1, 6> Hself = {},
337  OptionalJacobian<1, 6> Hpose = {}) const;
338 
344  Unit3 bearing(const Point3& point, OptionalJacobian<2, 6> Hself = {},
345  OptionalJacobian<2, 3> Hpoint = {}) const;
346 
353  Unit3 bearing(const Pose3& pose, OptionalJacobian<2, 6> Hself = {},
354  OptionalJacobian<2, 6> Hpose = {}) const;
355 
359 
365  inline static std::pair<size_t, size_t> translationInterval() {
366  return {3, 5};
367  }
368 
374  static std::pair<size_t, size_t> rotationInterval() {
375  return {0, 2};
376  }
377 
383  Pose3 slerp(double t, const Pose3& other, OptionalJacobian<6, 6> Hx = {},
384  OptionalJacobian<6, 6> Hy = {}) const;
385 
387  Vector vec(OptionalJacobian<16, 6> H = {}) const;
388 
390  GTSAM_EXPORT
391  friend std::ostream &operator<<(std::ostream &os, const Pose3& p);
392 
396 
397 #ifdef GTSAM_ALLOW_DEPRECATED_SINCE_V43
398  static inline LieAlgebra wedge(double wx, double wy, double wz, double vx,
400  double vy, double vz) {
401  return Hat((TangentVector() << wx, wy, wz, vx, vy, vz).finished());
402  }
403 #endif
404 
406  private:
407 #if GTSAM_ENABLE_BOOST_SERIALIZATION
408 
409  friend class boost::serialization::access;
410  template<class Archive>
411  void serialize(Archive & ar, const unsigned int /*version*/) {
412  ar & BOOST_SERIALIZATION_NVP(R_);
413  ar & BOOST_SERIALIZATION_NVP(t_);
414  }
415 #endif
416 
418 #ifdef GTSAM_USE_QUATERNIONS
419  // Align if we are using Quaternions
420  public:
422 #endif
423 };
424 // Pose3 class
425 
426 #ifdef GTSAM_ALLOW_DEPRECATED_SINCE_V43
427 template<>
429 inline Matrix wedge<Pose3>(const Vector& xi) {
430  // NOTE(chris): Need eval() as workaround for Apple clang + avx2.
431  return Matrix(Pose3::Hat(xi)).eval();
432 }
433 #endif
434 
435 // Convenience typedef
436 using Pose3Pair = std::pair<Pose3, Pose3>;
437 using Pose3Pairs = std::vector<std::pair<Pose3, Pose3> >;
438 
439 // For MATLAB wrapper
440 typedef std::vector<Pose3> Pose3Vector;
441 
442 template <>
443 struct traits<Pose3> : public internal::MatrixLieGroup<Pose3> {};
444 
445 template <>
446 struct traits<const Pose3> : public internal::MatrixLieGroup<Pose3> {};
447 
448 // bearing and range traits, used in RangeFactor
449 template <>
450 struct Bearing<Pose3, Point3> : HasBearing<Pose3, Point3, Unit3> {};
451 
452 template<>
453 struct Bearing<Pose3, Pose3> : HasBearing<Pose3, Pose3, Unit3> {};
454 
455 template <typename T>
456 struct Range<Pose3, T> : HasRange<Pose3, T, double> {};
457 
458 } // namespace gtsam
gtsam::Pose3Pair
std::pair< Pose3, Pose3 > Pose3Pair
Definition: Pose3.h:436
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::Pose3Vector
std::vector< Pose3 > Pose3Vector
Definition: Pose3.h:440
gtsam::Pose3::R_
Rot3 R_
Rotation gRp, between global and pose frame.
Definition: Pose3.h:46
gtsam::Pose3::Hat
static Matrix4 Hat(const Vector6 &xi)
Definition: Pose3.cpp:164
gtsam::Point3Pairs
std::vector< Point3Pair > Point3Pairs
Definition: Point3.h:45
gtsam::translation
Point3_ translation(const Pose3_ &pose)
Definition: slam/expressions.h:97
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
s
RealScalar s
Definition: level1_cplx_impl.h:126
e
Array< double, 1, 3 > e(1./3., 0.5, 2.)
gtsam::operator<<
std::ostream & operator<<(std::ostream &os, const Dih6 &m)
Definition: testGroup.cpp:109
screwPose2::xi
Vector xi
Definition: testPose2.cpp:169
gtsam::Pose3::rotationInterval
static std::pair< size_t, size_t > rotationInterval()
Definition: Pose3.h:374
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::Pose3::Pose3
Pose3(const Matrix &T)
Definition: Pose3.h:71
gtsam::Pose3::Pose3
Pose3(const Rot3 &R, const Point3 &t)
Definition: Pose3.h:63
gtsam::Pose3::operator*
Point3 operator*(const Point3 &point) const
Definition: Pose3.h:259
gtsam::Matrix
Eigen::MatrixXd Matrix
Definition: base/Matrix.h:39
X
#define X
Definition: icosphere.cpp:20
gtsam::interpolateRt
Pose3_ interpolateRt(const Pose3_ &p, const Pose3_ &q, const Double_ &t)
Definition: slam/expressions.h:61
Point3.h
3D Point
os
ofstream os("timeSchurFactors.csv")
gtsam::Pose3::t_
Point3 t_
Translation gPp, from global origin to pose frame origin.
Definition: Pose3.h:47
gtsam::Vector
Eigen::VectorXd Vector
Definition: Vector.h:39
gtsam::Pose3::Pose3
Pose3()
Definition: Pose3.h:55
gtsam::Pose3::Identity
static Pose3 Identity()
identity for group operation
Definition: Pose3.h:109
gtsam::Pose3::operator*
Pose3 operator*(const Pose3 &T) const
compose syntactic sugar
Definition: Pose3.h:117
Rot3.h
3D rotation represented as a rotation matrix or quaternion
gtsam::Pose3::adjoint_
static Vector6 adjoint_(const Vector6 &xi, const Vector6 &y)
Definition: Pose3.h:199
gtsam::range
Double_ range(const Point2_ &p, const Point2_ &q)
Definition: slam/expressions.h:30
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::transformFrom
Point3_ transformFrom(const Pose3_ &x, const Point3_ &p)
Definition: slam/expressions.h:47
vy
StridedVectorType vy(make_vector(y, *n, std::abs(*incy)))
gtsam::Pose3::Translation
Point3 Translation
Definition: Pose3.h:42
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:256
gtsam::Rot3
Rot3 is a 3D rotation represented as a rotation matrix if the preprocessor symbol GTSAM_USE_QUATERNIO...
Definition: Rot3.h:58
gtsam::Pose3
Definition: Pose3.h:37
gtsam::Pose3::y
double y() const
get y
Definition: Pose3.h:296
example2::aTb
Point3 aTb
Definition: testEssentialMatrixFactor.cpp:585
gtsam::Pose3Pairs
std::vector< std::pair< Pose3, Pose3 > > Pose3Pairs
Definition: Pose3.h:437
Eigen::Triplet< double >
gtsam::Range
Definition: BearingRange.h:41
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::b
const G & b
Definition: Group.h:79
gtsam::Pose3::ChartAtOrigin
Definition: Pose3.h:218
a
ArrayXXi a
Definition: Array_initializer_list_23_cxx11.cpp:1
pose2
Definition: testFrobeniusFactor.cpp:193
Lie.h
Base class and basic functions for Lie types.
gtsam
traits
Definition: ABC.h:17
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::HasRange
Definition: BearingRange.h:197
gtsam::Pose3::translationInterval
static std::pair< size_t, size_t > translationInterval()
Definition: Pose3.h:365
p
float * p
Definition: Tutorial_Map_using.cpp:9
gtsam::Pose3::x
double x() const
get x
Definition: Pose3.h:291
gtsam::LieGroup
Definition: Lie.h:37
gtsam::tol
const G double tol
Definition: Group.h:79
gtsam::Point3
Vector3 Point3
Definition: Point3.h:38
gtsam::Pose3::Rotation
Rot3 Rotation
Definition: Pose3.h:41
Eigen::Matrix< double, 6, 6 >
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
gtsam::Pose3::LieAlgebra
Matrix4 LieAlgebra
Definition: Pose3.h:144
gtsam::transformPoseTo
Pose3_ transformPoseTo(const Pose3_ &p, const Pose3_ &q)
Definition: slam/expressions.h:57
align_3::t
Point2 t(10, 10)
Pose3
Definition: testDependencies.h:3
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
R
Rot2 R(Rot2::fromAngle(0.1))
gtsam::Pose3::adjointMap_
static Matrix6 adjointMap_(const Vector6 &xi)
Definition: Pose3.h:198
gtsam::Pose3::z
double z() const
get z
Definition: Pose3.h:301
vx
StridedVectorType vx(make_vector(x, *n, std::abs(*incx)))
gtsam::Pose2
Definition: Pose2.h:39
HR
#define HR
Definition: mincover.c:26


gtsam
Author(s):
autogenerated on Wed May 28 2025 03:02:35