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) :
59  R_(pose.R_), t_(pose.t_) {
60  }
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,
78  OptionalJacobian<6, 3> HR = boost::none,
79  OptionalJacobian<6, 3> Ht = boost::none);
80 
86  static boost::optional<Pose3> Align(const std::vector<Point3Pair>& abPointPairs);
87 
91 
93  void print(const std::string& s = "") const;
94 
96  bool equals(const Pose3& pose, double tol = 1e-9) const;
97 
101 
103  static Pose3 identity() {
104  return Pose3();
105  }
106 
108  Pose3 inverse() const;
109 
111  Pose3 operator*(const Pose3& T) const {
112  return Pose3(R_ * T.R_, t_ + R_ * T.t_);
113  }
114 
129  Pose3 interpolateRt(const Pose3& T, double t) const {
130  return Pose3(interpolate<Rot3>(R_, T.R_, t),
131  interpolate<Point3>(t_, T.t_, t));
132  }
133 
137 
139  static Pose3 Expmap(const Vector6& xi, OptionalJacobian<6, 6> Hxi = boost::none);
140 
142  static Vector6 Logmap(const Pose3& pose, OptionalJacobian<6, 6> Hpose = boost::none);
143 
148  Matrix6 AdjointMap() const;
149 
154  Vector6 Adjoint(const Vector6& xi_b) const {
155  return AdjointMap() * xi_b;
156  }
157 
173  static Matrix6 adjointMap(const Vector6 &xi);
174 
178  static Vector6 adjoint(const Vector6 &xi, const Vector6 &y,
179  OptionalJacobian<6, 6> Hxi = boost::none);
180 
181  // temporary fix for wrappers until case issue is resolved
182  static Matrix6 adjointMap_(const Vector6 &xi) { return adjointMap(xi);}
183  static Vector6 adjoint_(const Vector6 &xi, const Vector6 &y) { return adjoint(xi, y);}
184 
188  static Vector6 adjointTranspose(const Vector6& xi, const Vector6& y,
189  OptionalJacobian<6, 6> Hxi = boost::none);
190 
192  static Matrix6 ExpmapDerivative(const Vector6& xi);
193 
195  static Matrix6 LogmapDerivative(const Pose3& xi);
196 
197  // Chart at origin, depends on compile-time flag GTSAM_POSE3_EXPMAP
198  struct ChartAtOrigin {
199  static Pose3 Retract(const Vector6& xi, ChartJacobian Hxi = boost::none);
200  static Vector6 Local(const Pose3& pose, ChartJacobian Hpose = boost::none);
201  };
202 
212  static Matrix3 ComputeQforExpmapDerivative(
213  const Vector6& xi, double nearZeroThreshold = 1e-5);
214 
215  using LieGroup<Pose3, 6>::inverse; // version with derivative
216 
224  static Matrix wedge(double wx, double wy, double wz, double vx, double vy,
225  double vz) {
226  return (Matrix(4, 4) << 0., -wz, wy, vx, wz, 0., -wx, vy, -wy, wx, 0., vz, 0., 0., 0., 0.).finished();
227  }
228 
232 
241  boost::none, OptionalJacobian<3, 3> Hpoint = boost::none) const;
242 
244  inline Point3 operator*(const Point3& point) const {
245  return transformFrom(point);
246  }
247 
255  Point3 transformTo(const Point3& point, OptionalJacobian<3, 6> Hself =
256  boost::none, OptionalJacobian<3, 3> Hpoint = boost::none) const;
257 
261 
263  const Rot3& rotation(OptionalJacobian<3, 6> Hself = boost::none) const;
264 
266  const Point3& translation(OptionalJacobian<3, 6> Hself = boost::none) const;
267 
269  double x() const {
270  return t_.x();
271  }
272 
274  double y() const {
275  return t_.y();
276  }
277 
279  double z() const {
280  return t_.z();
281  }
282 
284  Matrix4 matrix() const;
285 
291  Pose3 transformPoseFrom(const Pose3& aTb, OptionalJacobian<6, 6> Hself = boost::none,
292  OptionalJacobian<6, 6> HaTb = boost::none) const;
293 
298  Pose3 transformPoseTo(const Pose3& wTb, OptionalJacobian<6, 6> Hself = boost::none,
299  OptionalJacobian<6, 6> HwTb = boost::none) const;
300 
306  double range(const Point3& point, OptionalJacobian<1, 6> Hself = boost::none,
307  OptionalJacobian<1, 3> Hpoint = boost::none) const;
308 
314  double range(const Pose3& pose, OptionalJacobian<1, 6> Hself = boost::none,
315  OptionalJacobian<1, 6> Hpose = boost::none) const;
316 
322  Unit3 bearing(const Point3& point, OptionalJacobian<2, 6> Hself = boost::none,
323  OptionalJacobian<2, 3> Hpoint = boost::none) const;
324 
331  Unit3 bearing(const Pose3& pose, OptionalJacobian<2, 6> Hself = boost::none,
332  OptionalJacobian<2, 6> Hpose = boost::none) const;
333 
337 
343  inline static std::pair<size_t, size_t> translationInterval() {
344  return std::make_pair(3, 5);
345  }
346 
352  static std::pair<size_t, size_t> rotationInterval() {
353  return std::make_pair(0, 2);
354  }
355 
357  GTSAM_EXPORT
358  friend std::ostream &operator<<(std::ostream &os, const Pose3& p);
359 
360  private:
362  friend class boost::serialization::access;
363  template<class Archive>
364  void serialize(Archive & ar, const unsigned int /*version*/) {
365  ar & BOOST_SERIALIZATION_NVP(R_);
366  ar & BOOST_SERIALIZATION_NVP(t_);
367  }
369 
370 #ifdef GTSAM_USE_QUATERNIONS
371  // Align if we are using Quaternions
372  public:
374 #endif
375 };
376 // Pose3 class
377 
385 template<>
386 inline Matrix wedge<Pose3>(const Vector& xi) {
387  return Pose3::wedge(xi(0), xi(1), xi(2), xi(3), xi(4), xi(5));
388 }
389 
390 // Convenience typedef
391 using Pose3Pair = std::pair<Pose3, Pose3>;
392 using Pose3Pairs = std::vector<std::pair<Pose3, Pose3> >;
393 
394 // For MATLAB wrapper
395 typedef std::vector<Pose3> Pose3Vector;
396 
397 template <>
398 struct traits<Pose3> : public internal::LieGroup<Pose3> {};
399 
400 template <>
401 struct traits<const Pose3> : public internal::LieGroup<Pose3> {};
402 
403 // bearing and range traits, used in RangeFactor
404 template <>
405 struct Bearing<Pose3, Point3> : HasBearing<Pose3, Point3, Unit3> {};
406 
407 template<>
408 struct Bearing<Pose3, Pose3> : HasBearing<Pose3, Pose3, Unit3> {};
409 
410 template <typename T>
411 struct Range<Pose3, T> : HasRange<Pose3, T, double> {};
412 
413 } // namespace gtsam
void print(const Matrix &A, const string &s, ostream &stream)
Definition: Matrix.cpp:155
static Matrix6 adjointMap_(const Vector6 &xi)
Definition: Pose3.h:182
Point3 t_
Translation gPp, from global origin to pose frame origin.
Definition: Pose3.h:47
std::ostream & operator<<(std::ostream &os, const Dih6 &m)
Definition: testGroup.cpp:109
Scalar * y
Point3 operator*(const Point3 &point) const
Definition: Pose3.h:244
Pose3 interpolateRt(const Pose3 &T, double t) const
Definition: Pose3.h:129
Rot3_ rotation(const Pose3_ &pose)
void adjoint(const MatrixType &m)
Definition: adjoint.cpp:67
Vector6 Adjoint(const Vector6 &xi_b) const
FIXME Not tested - marked as incorrect.
Definition: Pose3.h:154
std::vector< Pose3 > Pose3Vector
Definition: Pose3.h:395
Rot3 R_
Rotation gRp, between global and pose frame.
Definition: Pose3.h:46
Eigen::MatrixXd Matrix
Definition: base/Matrix.h:43
Rot2 R(Rot2::fromAngle(0.1))
Pose2_ Expmap(const Vector3_ &xi)
static Matrix wedge(double wx, double wy, double wz, double vx, double vy, double vz)
Definition: Pose3.h:224
double x() const
get x
Definition: Pose3.h:269
Point3 point(10, 0,-5)
std::vector< std::pair< Pose3, Pose3 > > Pose3Pairs
Definition: Pose3.h:392
static Pose3 identity()
identity for group operation
Definition: Pose3.h:103
Represents a 3D point on a unit sphere.
Definition: Unit3.h:42
StridedVectorType vy(make_vector(y,*n, std::abs(*incy)))
Point3_ transformFrom(const Pose3_ &x, const Point3_ &p)
Eigen::VectorXd Vector
Definition: Vector.h:38
Pose3(const Pose3 &pose)
Definition: Pose3.h:58
static const Pose3 pose(Rot3(Vector3(1,-1,-1).asDiagonal()), Point3(0, 0, 0.5))
static std::pair< size_t, size_t > rotationInterval()
Definition: Pose3.h:352
double y() const
get y
Definition: Pose3.h:274
Pose3(const Matrix &T)
Definition: Pose3.h:71
Array< double, 1, 3 > e(1./3., 0.5, 2.)
RealScalar s
Pose3(const Rot3 &R, const Point3 &t)
Definition: Pose3.h:63
Matrix wedge< Pose3 >(const Vector &xi)
Definition: Pose3.h:386
Base class and basic functions for Lie types.
static std::pair< size_t, size_t > translationInterval()
Definition: Pose3.h:343
Vector xi
Definition: testPose2.cpp:150
traits
Definition: chartTesting.h:28
Rot3 Rotation
Definition: Pose3.h:41
ofstream os("timeSchurFactors.csv")
Both LieGroupTraits and Testable.
Definition: Lie.h:228
Bearing-Range product.
3D Point
Point3 Translation
Definition: Pose3.h:42
#define HR
Definition: mincover.c:26
float * p
#define GTSAM_MAKE_ALIGNED_OPERATOR_NEW
Definition: types.h:269
static Vector6 adjoint_(const Vector6 &xi, const Vector6 &y)
Definition: Pose3.h:183
Line3 transformTo(const Pose3 &wTc, const Line3 &wL, OptionalJacobian< 4, 6 > Dpose, OptionalJacobian< 4, 4 > Dline)
Definition: Line3.cpp:94
StridedVectorType vx(make_vector(x,*n, std::abs(*incx)))
const G double tol
Definition: Group.h:83
static const Pose3 pose2
Vector3 Point3
Definition: Point3.h:35
std::pair< Pose3, Pose3 > Pose3Pair
Definition: Pose3.h:391
Map< Matrix< T, Dynamic, Dynamic, ColMajor >, 0, OuterStride<> > matrix(T *data, int rows, int cols, int stride)
Pose3 operator*(const Pose3 &T) const
compose syntactic sugar
Definition: Pose3.h:111
EIGEN_DEVICE_FUNC const InverseReturnType inverse() const
Point2 t(10, 10)
void serialize(Archive &ar, const unsigned int)
Definition: Pose3.h:364
3D rotation represented as a rotation matrix or quaternion
double z() const
get z
Definition: Pose3.h:279


gtsam
Author(s):
autogenerated on Sat May 8 2021 02:43:27