Pose3.cpp
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 #include <gtsam/base/concepts.h>
18 #include <gtsam/geometry/Pose2.h>
19 #include <gtsam/geometry/Pose3.h>
20 #include <gtsam/geometry/Rot3.h>
22 
23 #include <cmath>
24 #include <iostream>
25 #include <string>
26 
27 namespace gtsam {
28 
31 
32 /* ************************************************************************* */
33 Pose3::Pose3(const Pose2& pose2) :
34  R_(Rot3::Rodrigues(0, 0, pose2.theta())), t_(
35  Point3(pose2.x(), pose2.y(), 0)) {
36 }
37 
38 /* ************************************************************************* */
41  if (HR) *HR << I_3x3, Z_3x3;
42  if (Ht) *Ht << Z_3x3, R.transpose();
43  return Pose3(R, t);
44 }
45 
46 // Pose2 constructor Jacobian is always the same.
47 static const Matrix63 Hpose2 = (Matrix63() << //
48  0., 0., 0., //
49  0., 0., 0.,//
50  0., 0., 1.,//
51  1., 0., 0.,//
52  0., 1., 0.,//
53  0., 0., 0.).finished();
54 
56  if (H) *H << Hpose2;
57  return Pose3(p);
58 }
59 
60 /* ************************************************************************* */
62  Rot3 Rt = R_.inverse();
63  return Pose3(Rt, Rt * (-t_));
64 }
65 
66 /* ************************************************************************* */
67 // Calculate Adjoint map
68 // Ad_pose is 6*6 matrix that when applied to twist xi, returns Ad_pose(xi)
70  const Matrix3 R = R_.matrix();
71  Matrix3 A = skewSymmetric(t_.x(), t_.y(), t_.z()) * R;
72  Matrix6 adj;
73  adj << R, Z_3x3, A, R; // Gives [R 0; A R]
74  return adj;
75 }
76 
77 /* ************************************************************************* */
78 // Calculate AdjointMap applied to xi_b, with Jacobians
79 Vector6 Pose3::Adjoint(const Vector6& xi_b, OptionalJacobian<6, 6> H_pose,
80  OptionalJacobian<6, 6> H_xib) const {
81  const Matrix6 Ad = AdjointMap();
82 
83  // Jacobians
84  // D1 Ad_T(xi_b) = D1 Ad_T Ad_I(xi_b) = Ad_T * D1 Ad_I(xi_b) = Ad_T * ad_xi_b
85  // D2 Ad_T(xi_b) = Ad_T
86  // See docs/math.pdf for more details.
87  // In D1 calculation, we could be more efficient by writing it out, but do not
88  // for readability
89  if (H_pose) *H_pose = -Ad * adjointMap(xi_b);
90  if (H_xib) *H_xib = Ad;
91 
92  return Ad * xi_b;
93 }
94 
95 /* ************************************************************************* */
97 Vector6 Pose3::AdjointTranspose(const Vector6& x, OptionalJacobian<6, 6> H_pose,
98  OptionalJacobian<6, 6> H_x) const {
99  const Matrix6 Ad = AdjointMap();
100  const Vector6 AdTx = Ad.transpose() * x;
101 
102  // Jacobians
103  // See docs/math.pdf for more details.
104  if (H_pose) {
105  const auto w_T_hat = skewSymmetric(AdTx.head<3>()),
106  v_T_hat = skewSymmetric(AdTx.tail<3>());
107  *H_pose << w_T_hat, v_T_hat, //
108  /* */ v_T_hat, Z_3x3;
109  }
110  if (H_x) {
111  *H_x = Ad.transpose();
112  }
113 
114  return AdTx;
115 }
116 
117 /* ************************************************************************* */
118 Matrix6 Pose3::adjointMap(const Vector6& xi) {
119  Matrix3 w_hat = skewSymmetric(xi(0), xi(1), xi(2));
120  Matrix3 v_hat = skewSymmetric(xi(3), xi(4), xi(5));
121  Matrix6 adj;
122  adj << w_hat, Z_3x3, v_hat, w_hat;
123 
124  return adj;
125 }
126 
127 /* ************************************************************************* */
128 Vector6 Pose3::adjoint(const Vector6& xi, const Vector6& y,
130  if (Hxi) {
131  Hxi->setZero();
132  for (int i = 0; i < 6; ++i) {
133  Vector6 dxi;
134  dxi.setZero();
135  dxi(i) = 1.0;
136  Matrix6 Gi = adjointMap(dxi);
137  Hxi->col(i) = Gi * y;
138  }
139  }
140  const Matrix6& ad_xi = adjointMap(xi);
141  if (H_y) *H_y = ad_xi;
142  return ad_xi * y;
143 }
144 
145 /* ************************************************************************* */
146 Vector6 Pose3::adjointTranspose(const Vector6& xi, const Vector6& y,
148  if (Hxi) {
149  Hxi->setZero();
150  for (int i = 0; i < 6; ++i) {
151  Vector6 dxi;
152  dxi.setZero();
153  dxi(i) = 1.0;
154  Matrix6 GTi = adjointMap(dxi).transpose();
155  Hxi->col(i) = GTi * y;
156  }
157  }
158  const Matrix6& adT_xi = adjointMap(xi).transpose();
159  if (H_y) *H_y = adT_xi;
160  return adT_xi * y;
161 }
162 
163 /* ************************************************************************* */
164 Matrix4 Pose3::Hat(const Vector6& xi) {
165  Matrix4 X;
166  const double wx = xi(0), wy = xi(1), wz = xi(2), vx = xi(3), vy = xi(4), vz = xi(5);
167  X << 0., -wz, wy, vx, wz, 0., -wx, vy, -wy, wx, 0., vz, 0., 0., 0., 0.;
168  return X;
169 }
170 
171 /* ************************************************************************* */
172 Vector6 Pose3::Vee(const Matrix4& Xi) {
173  Vector6 xi;
174  xi << Xi(2, 1), Xi(0, 2), Xi(1, 0), Xi(0, 3), Xi(1, 3), Xi(2, 3);
175  return xi;
176 }
177 
178 /* ************************************************************************* */
179 void Pose3::print(const std::string& s) const {
180  std::cout << (s.empty() ? s : s + " ") << *this << std::endl;
181 }
182 
183 /* ************************************************************************* */
184 bool Pose3::equals(const Pose3& pose, double tol) const {
185  return R_.equals(pose.R_, tol) && traits<Point3>::Equals(t_, pose.t_, tol);
186 }
187 
188 /* ************************************************************************* */
192  OptionalJacobian<6, 1> Ht) const {
193  if(Hself || Harg || Ht){
194  typename MakeJacobian<Rot3, Rot3>::type HselfRot, HargRot;
195  typename MakeJacobian<Rot3, double>::type HtRot;
196  typename MakeJacobian<Point3, Point3>::type HselfPoint, HargPoint;
197  typename MakeJacobian<Point3, double>::type HtPoint;
198 
199  Rot3 Rint = interpolate<Rot3>(R_, T.R_, t, HselfRot, HargRot, HtRot);
200  Point3 Pint = interpolate<Point3>(t_, T.t_, t, HselfPoint, HargPoint, HtPoint);
201  Pose3 result = Pose3(Rint, Pint);
202 
203  if(Hself) *Hself << HselfRot, Z_3x3, Z_3x3, Rint.transpose() * R_.matrix() * HselfPoint;
204  if(Harg) *Harg << HargRot, Z_3x3, Z_3x3, Rint.transpose() * T.R_.matrix() * HargPoint;
205  if(Ht) *Ht << HtRot, Rint.transpose() * HtPoint;
206 
207  return result;
208  }
209  return Pose3(interpolate<Rot3>(R_, T.R_, t),
210  interpolate<Point3>(t_, T.t_, t));
211 
212 }
213 
214 /* ************************************************************************* */
215 // Expmap is implemented in so3::ExpmapFunctor::expmap, based on Ethan Eade's
216 // elegant Lie group document, at https://www.ethaneade.org/lie.pdf.
218  // Get angular velocity omega and translational velocity v from twist xi
219  const Vector3 w = xi.head<3>(), v = xi.tail<3>();
220 
221  // Instantiate functor for Dexp-related operations:
222  const so3::DexpFunctor local(w);
223 
224  // Compute rotation using Expmap
225 #ifdef GTSAM_USE_QUATERNIONS
227 #else
228  const Rot3 R(local.expmap());
229 #endif
230 
231  // The translation t = local.leftJacobian() * v.
232  // Here we call applyLeftJacobian, which is faster if you don't need
233  // Jacobians, and returns Jacobian of t with respect to w if asked.
234  // NOTE(Frank): t = applyLeftJacobian(v) does the same as the intuitive formulas
235  // t_parallel = w * w.dot(v); // translation parallel to axis
236  // w_cross_v = w.cross(v); // translation orthogonal to axis
237  // t = (w_cross_v - Rot3::Expmap(w) * w_cross_v + t_parallel) / theta2;
238  // but functor does not need R, deals automatically with the case where theta2
239  // is near zero, and also gives us the machinery for the Jacobians.
240  Matrix3 H;
241  const Vector3 t = local.applyLeftJacobian(v, Hxi ? &H : nullptr);
242 
243  if (Hxi) {
244  // The Jacobian of expmap is given by the right Jacobian of SO(3):
245  const Matrix3 Jr = local.rightJacobian();
246  // We are creating a Pose3, so we still need to chain H with R^T, the
247  // Jacobian of Pose3::Create with respect to t.
248  const Matrix3 Q = R.matrix().transpose() * H;
249  *Hxi << Jr, Z_3x3, // Jr here *is* the Jacobian of expmap
250  Q, Jr; // Here Jr = R^T * J_l, with J_l the Jacobian of t in v.
251  }
252 
253  return Pose3(R, t);
254 }
255 
256 /* ************************************************************************* */
258  const Vector3 w = Rot3::Logmap(pose.rotation());
259 
260  // Instantiate functor for Dexp-related operations:
261  const so3::DexpFunctor local(w);
262 
263  const Vector3 t = pose.translation();
264  const Vector3 u = local.applyLeftJacobianInverse(t);
265  Vector6 xi;
266  xi << w, u;
267  if (Hpose) *Hpose = LogmapDerivative(xi);
268  return xi;
269 }
270 
271 /* ************************************************************************* */
273 #ifdef GTSAM_POSE3_EXPMAP
274  return Expmap(xi, Hxi);
275 #else
276  Matrix3 DR;
277  Rot3 R = Rot3::Retract(xi.head<3>(), Hxi ? &DR : 0);
278  if (Hxi) {
279  *Hxi = I_6x6;
280  Hxi->topLeftCorner<3, 3>() = DR;
281  }
282  return Pose3(R, Point3(xi.tail<3>()));
283 #endif
284 }
285 
286 /* ************************************************************************* */
288 #ifdef GTSAM_POSE3_EXPMAP
289  return Logmap(pose, Hpose);
290 #else
291  Matrix3 DR;
292  Vector3 omega = Rot3::LocalCoordinates(pose.rotation(), Hpose ? &DR : 0);
293  if (Hpose) {
294  *Hpose = I_6x6;
295  Hpose->topLeftCorner<3, 3>() = DR;
296  }
297  Vector6 xi;
298  xi << omega, pose.translation();
299  return xi;
300 #endif
301 }
302 
303 /* ************************************************************************* */
305  Matrix6 J;
306  Expmap(xi, J);
307  return J;
308 }
309 
310 /* ************************************************************************* */
312  const Vector3 w = xi.head<3>();
313  Vector3 v = xi.segment<3>(3);
314 
315  // Instantiate functor for Dexp-related operations:
316  const so3::DexpFunctor local(w);
317 
318  // Call applyLeftJacobian to get its Jacobians
319  Matrix3 H_t_w;
320  local.applyLeftJacobian(v, H_t_w);
321 
322  // Multiply with R^T to account for NavState::Create Jacobian.
323  const Matrix3 R = local.expmap();
324  const Matrix3 Qt = R.transpose() * H_t_w;
325 
326  // Now compute the blocks of the LogmapDerivative Jacobian
327  const Matrix3 Jw = Rot3::LogmapDerivative(w);
328  const Matrix3 Qt2 = -Jw * Qt * Jw;
329 
330  Matrix6 J;
331  J << Jw, Z_3x3, Qt2, Jw;
332  return J;
333 }
334 
335 /* ************************************************************************* */
337  const Vector6 xi = Logmap(pose);
338  return LogmapDerivative(xi);
339 }
340 
341 /* ************************************************************************* */
343  if (Hself) *Hself << Z_3x3, rotation().matrix();
344  return t_;
345 }
346 
347 /* ************************************************************************* */
349  if (Hself) {
350  *Hself << I_3x3, Z_3x3;
351  }
352  return R_;
353 }
354 
355 /* ************************************************************************* */
356 Matrix4 Pose3::matrix() const {
357  static const auto A14 = Eigen::RowVector4d(0,0,0,1);
358  Matrix4 mat;
359  mat << R_.matrix(), t_, A14;
360  return mat;
361 }
362 
363 /* ************************************************************************* */
365  OptionalJacobian<6, 6> HaTb) const {
366  const Pose3& wTa = *this;
367  return wTa.compose(aTb, Hself, HaTb);
368 }
369 
370 /* ************************************************************************* */
372  OptionalJacobian<6, 6> HwTb) const {
373  if (Hself) *Hself = -wTb.inverse().AdjointMap() * AdjointMap();
374  if (HwTb) *HwTb = I_6x6;
375  const Pose3& wTa = *this;
376  return wTa.inverse() * wTb;
377 }
378 
379 /* ************************************************************************* */
381  OptionalJacobian<3, 3> Hpoint) const {
382  // Only get matrix once, to avoid multiple allocations,
383  // as well as multiple conversions in the Quaternion case
384  const Matrix3 R = R_.matrix();
385  if (Hself) {
386  Hself->leftCols<3>() = R * skewSymmetric(-point.x(), -point.y(), -point.z());
387  Hself->rightCols<3>() = R;
388  }
389  if (Hpoint) {
390  *Hpoint = R;
391  }
392  return R_ * point + t_;
393 }
394 
395 Matrix Pose3::transformFrom(const Matrix& points) const {
396  if (points.rows() != 3) {
397  throw std::invalid_argument("Pose3:transformFrom expects 3*N matrix.");
398  }
399  const Matrix3 R = R_.matrix();
400  return (R * points).colwise() + t_; // Eigen broadcasting!
401 }
402 
403 /* ************************************************************************* */
405  OptionalJacobian<3, 3> Hpoint) const {
406  // Only get transpose once, to avoid multiple allocations,
407  // as well as multiple conversions in the Quaternion case
408  const Matrix3 Rt = R_.transpose();
409  const Point3 q(Rt*(point - t_));
410  if (Hself) {
411  const double wx = q.x(), wy = q.y(), wz = q.z();
412  (*Hself) <<
413  0.0, -wz, +wy,-1.0, 0.0, 0.0,
414  +wz, 0.0, -wx, 0.0,-1.0, 0.0,
415  -wy, +wx, 0.0, 0.0, 0.0,-1.0;
416  }
417  if (Hpoint) {
418  *Hpoint = Rt;
419  }
420  return q;
421 }
422 
423 Matrix Pose3::transformTo(const Matrix& points) const {
424  if (points.rows() != 3) {
425  throw std::invalid_argument("Pose3:transformTo expects 3*N matrix.");
426  }
427  const Matrix3 Rt = R_.transpose();
428  return Rt * (points.colwise() - t_); // Eigen broadcasting!
429 }
430 
431 /* ************************************************************************* */
433  OptionalJacobian<1, 3> Hpoint) const {
434  Matrix36 D_local_pose;
435  Matrix3 D_local_point;
436  Point3 local = transformTo(point, Hself ? &D_local_pose : 0, Hpoint ? &D_local_point : 0);
437  if (!Hself && !Hpoint) {
438  return local.norm();
439  } else {
440  Matrix13 D_r_local;
441  const double r = norm3(local, D_r_local);
442  if (Hself) *Hself = D_r_local * D_local_pose;
443  if (Hpoint) *Hpoint = D_r_local * D_local_point;
444  return r;
445  }
446 }
447 
448 /* ************************************************************************* */
450  OptionalJacobian<1, 6> Hpose) const {
451  Matrix36 D_point_pose;
452  Matrix13 D_local_point;
453  Point3 point = pose.translation(Hpose ? &D_point_pose : 0);
454  double r = range(point, Hself, Hpose ? &D_local_point : 0);
455  if (Hpose) *Hpose = D_local_point * D_point_pose;
456  return r;
457 }
458 
459 /* ************************************************************************* */
461  OptionalJacobian<2, 3> Hpoint) const {
462  Matrix36 D_local_pose;
463  Matrix3 D_local_point;
464  Point3 local = transformTo(point, Hself ? &D_local_pose : 0, Hpoint ? &D_local_point : 0);
465  if (!Hself && !Hpoint) {
466  return Unit3(local);
467  } else {
468  Matrix23 D_b_local;
469  Unit3 b = Unit3::FromPoint3(local, D_b_local);
470  if (Hself) *Hself = D_b_local * D_local_pose;
471  if (Hpoint) *Hpoint = D_b_local * D_local_point;
472  return b;
473  }
474 }
475 
476 /* ************************************************************************* */
478  OptionalJacobian<2, 6> Hpose) const {
479  Matrix36 D_point_pose;
480  Matrix23 D_local_point;
481  Point3 point = pose.translation(Hpose ? &D_point_pose : 0);
482  Unit3 b = bearing(point, Hself, Hpose ? &D_local_point : 0);
483  if (Hpose) *Hpose = D_local_point * D_point_pose;
484  return b;
485 }
486 
487 /* ************************************************************************* */
488 std::optional<Pose3> Pose3::Align(const Point3Pairs &abPointPairs) {
489  const size_t n = abPointPairs.size();
490  if (n < 3) {
491  return {}; // we need at least three pairs
492  }
493 
494  // calculate centroids
495  const auto centroids = means(abPointPairs);
496 
497  // Add to form H matrix
498  Matrix3 H = Z_3x3;
499  for (const Point3Pair &abPair : abPointPairs) {
500  const Point3 da = abPair.first - centroids.first;
501  const Point3 db = abPair.second - centroids.second;
502  H += da * db.transpose();
503  }
504 
505  // ClosestTo finds rotation matrix closest to H in Frobenius sense
506  const Rot3 aRb = Rot3::ClosestTo(H);
507  const Point3 aTb = centroids.first - aRb * centroids.second;
508  return Pose3(aRb, aTb);
509 }
510 
511 std::optional<Pose3> Pose3::Align(const Matrix& a, const Matrix& b) {
512  if (a.rows() != 3 || b.rows() != 3 || a.cols() != b.cols()) {
513  throw std::invalid_argument(
514  "Pose3:Align expects 3*N matrices of equal shape.");
515  }
516  Point3Pairs abPointPairs;
517  for (Eigen::Index j = 0; j < a.cols(); j++) {
518  abPointPairs.emplace_back(a.col(j), b.col(j));
519  }
520  return Pose3::Align(abPointPairs);
521 }
522 
523 /* ************************************************************************* */
525  return interpolate(*this, other, t, Hx, Hy);
526 }
527 
528 /* ************************************************************************* */
529 // Compute vectorized Lie algebra generators for SE(3)
533  Matrix16x6 G;
534  for (size_t j = 0; j < 6; j++) {
535  const Matrix4 X = Pose3::Hat(Vector::Unit(6, j));
536  G.col(j) = Eigen::Map<const Vector16>(X.data());
537  }
538  return G;
539 }
540 
542  // Vectorize
543  const Matrix4 M = matrix();
544  const Vector X = Eigen::Map<const Vector16>(M.data());
545 
546  // If requested, calculate H as (I_4 \oplus M) * G.
547  if (H) {
548  static const Matrix16x6 G = VectorizedGenerators(); // static to compute only once
549  for (size_t i = 0; i < 4; i++)
550  H->block(i * 4, 0, 4, dimension) = M * G.block(i * 4, 0, 4, dimension);
551  }
552 
553  return X;
554 }
555 
556 /* ************************************************************************* */
557 std::ostream &operator<<(std::ostream &os, const Pose3& pose) {
558  // Both Rot3 and Point3 have ostream definitions so we use them.
559  os << "R: " << pose.rotation() << "\n";
560  os << "t: " << pose.translation().transpose();
561  return os;
562 }
563 
564 } // namespace gtsam
w
RowVector3d w
Definition: Matrix_resize_int.cpp:3
gtsam::Pose3::slerp
Pose3 slerp(double t, const Pose3 &other, OptionalJacobian< 6, 6 > Hx={}, OptionalJacobian< 6, 6 > Hy={}) const
Spherical Linear interpolation between *this and other.
Definition: Pose3.cpp:524
gtsam::LieGroup< Pose3, 6 >::dimension
constexpr static auto dimension
Definition: Lie.h:39
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::VectorizedGenerators
static Matrix93 VectorizedGenerators()
Definition: Pose2.cpp:328
gtsam::Point3Pair
std::pair< Point3, Point3 > Point3Pair
Definition: Point3.h:42
Pose2.h
2D Pose
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::Pose3::LogmapDerivative
static Matrix6 LogmapDerivative(const Vector6 &xi)
Derivative of Logmap.
Definition: Pose3.cpp:311
pose
static const Pose3 pose(Rot3(Vector3(1, -1, -1).asDiagonal()), Point3(0, 0, 0.5))
gtsam::Pose3::transformTo
Point3 transformTo(const Point3 &point, OptionalJacobian< 3, 6 > Hself={}, OptionalJacobian< 3, 3 > Hpoint={}) const
takes point in world coordinates and transforms it to Pose coordinates
Definition: Pose3.cpp:404
aRb
Rot3 aRb
Definition: testFundamentalMatrix.cpp:146
concepts.h
Concept-checking macros for geometric objects Each macro instantiates a concept check structure,...
s
RealScalar s
Definition: level1_cplx_impl.h:126
gtsam::Pose3::vec
Vector vec(OptionalJacobian< 16, 6 > H={}) const
Return vectorized SE(3) matrix in column order.
Definition: Pose3.cpp:541
screwPose2::xi
Vector xi
Definition: testPose2.cpp:169
gtsam::Pose3::FromPose2
static Pose3 FromPose2(const Pose2 &p, OptionalJacobian< 6, 3 > H={})
Definition: Pose3.cpp:55
gtsam::Pose3::Vee
static Vector6 Vee(const Matrix4 &X)
Vee maps from Lie algebra to tangent vector.
Definition: Pose3.cpp:172
gtsam::Pose3::adjointTranspose
static Vector6 adjointTranspose(const Vector6 &xi, const Vector6 &y, OptionalJacobian< 6, 6 > Hxi={}, OptionalJacobian< 6, 6 > H_y={})
Definition: Pose3.cpp:146
gtsam::Rot3::ClosestTo
static Rot3 ClosestTo(const Matrix3 &M)
Definition: Rot3.h:275
gtsam::LieGroup::compose
Class compose(const Class &g) const
Definition: Lie.h:48
gtsam::Pose3::Logmap
static Vector6 Logmap(const Pose3 &pose, OptionalJacobian< 6, 6 > Hpose={})
Log map at identity - return the canonical coordinates of this rotation.
Definition: Pose3.cpp:257
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::Expmap
static Pose3 Expmap(const Vector6 &xi, OptionalJacobian< 6, 6 > Hxi={})
Exponential map at identity - create a rotation from canonical coordinates .
Definition: Pose3.cpp:217
gtsam::Matrix
Eigen::MatrixXd Matrix
Definition: base/Matrix.h:39
X
#define X
Definition: icosphere.cpp:20
concepts.h
gtsam::Vector3
Eigen::Vector3d Vector3
Definition: Vector.h:44
mat
MatrixXf mat
Definition: Tutorial_AdvancedInitialization_CommaTemporary.cpp:1
os
ofstream os("timeSchurFactors.csv")
gtsam::Pose3::t_
Point3 t_
Translation gPp, from global origin to pose frame origin.
Definition: Pose3.h:47
gtsam::means
Point2Pair means(const std::vector< Point2Pair > &abPointPairs)
Calculate the two means of a set of Point2 pairs.
Definition: Point2.cpp:116
gtsam::Vector
Eigen::VectorXd Vector
Definition: Vector.h:39
gtsam::skewSymmetric
Matrix3 skewSymmetric(double wx, double wy, double wz)
Definition: base/Matrix.h:381
result
Values result
Definition: OdometryOptimize.cpp:8
Q
Quaternion Q
Definition: testQuaternion.cpp:27
gtsam::Rot3::LogmapDerivative
static Matrix3 LogmapDerivative(const Vector3 &x)
Derivative of Logmap.
Definition: Rot3.cpp:244
gtsam::Pose3::Pose3
Pose3()
Definition: Pose3.h:55
gtsam::Pose3::matrix
Matrix4 matrix() const
Definition: Pose3.cpp:356
gtsam::Pose3::range
double range(const Point3 &point, OptionalJacobian< 1, 6 > Hself={}, OptionalJacobian< 1, 3 > Hpoint={}) const
Definition: Pose3.cpp:432
Rot3.h
3D rotation represented as a rotation matrix or quaternion
biased_x_rotation::omega
const double omega
Definition: testPreintegratedRotation.cpp:32
gtsam::Pose3::transformPoseFrom
Pose3 transformPoseFrom(const Pose3 &aTb, OptionalJacobian< 6, 6 > Hself={}, OptionalJacobian< 6, 6 > HaTb={}) const
Definition: Pose3.cpp:364
n
int n
Definition: BiCGSTAB_simple.cpp:1
gtsam::Pose3::AdjointTranspose
Vector6 AdjointTranspose(const Vector6 &x, OptionalJacobian< 6, 6 > H_this={}, OptionalJacobian< 6, 6 > H_x={}) const
The dual version of Adjoint.
Definition: Pose3.cpp:97
gtsam::Pose3::print
void print(const std::string &s="") const
print with optional string
Definition: Pose3.cpp:179
gtsam_unstable.tests.test_ProjectionFactorRollingShutter.point
point
Definition: test_ProjectionFactorRollingShutter.py:25
gtsam::Pose3::transformPoseTo
Pose3 transformPoseTo(const Pose3 &wTb, OptionalJacobian< 6, 6 > Hself={}, OptionalJacobian< 6, 6 > HwTb={}) const
Definition: Pose3.cpp:371
Expmap
Pose2_ Expmap(const Vector3_ &xi)
Definition: InverseKinematicsExampleExpressions.cpp:47
gtsam::Pose3::Adjoint
Vector6 Adjoint(const Vector6 &xi_b, OptionalJacobian< 6, 6 > H_this={}, OptionalJacobian< 6, 6 > H_xib={}) const
Definition: Pose3.cpp:79
gtsam::LieGroup< Rot3, 3 >::Retract
static Rot3 Retract(const TangentVector &v)
Retract at origin: possible in Lie group because it has an identity.
Definition: Lie.h:111
J
JacobiRotation< float > J
Definition: Jacobi_makeJacobi.cpp:3
A
Definition: test_numpy_dtypes.cpp:300
vy
StridedVectorType vy(make_vector(y, *n, std::abs(*incy)))
gtsam::Pose3::Create
static Pose3 Create(const Rot3 &R, const Point3 &t, OptionalJacobian< 6, 3 > HR={}, OptionalJacobian< 6, 3 > Ht={})
Named constructor with derivatives.
Definition: Pose3.cpp:39
j
std::ptrdiff_t j
Definition: tut_arithmetic_redux_minmax.cpp:2
Eigen::numext::q
EIGEN_DEVICE_FUNC const Scalar & q
Definition: SpecialFunctionsImpl.h:1984
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::inverse
Pose3 inverse() const
inverse transformation with derivatives
Definition: Pose3.cpp:61
gtsam::Pose3::interpolateRt
Pose3 interpolateRt(const Pose3 &T, double t, OptionalJacobian< 6, 6 > Hself={}, OptionalJacobian< 6, 6 > Harg={}, OptionalJacobian< 6, 1 > Ht={}) const
Definition: Pose3.cpp:189
gtsam::Pose3::ExpmapDerivative
static Matrix6 ExpmapDerivative(const Vector6 &xi)
Derivative of Expmap.
Definition: Pose3.cpp:304
gtsam::Pose3::equals
bool equals(const Pose3 &pose, double tol=1e-9) const
assert equality up to a tolerance
Definition: Pose3.cpp:184
gtsam::Pose3::translation
const Point3 & translation(OptionalJacobian< 3, 6 > Hself={}) const
get translation
Definition: Pose3.cpp:342
gtsam::Pose3::AdjointMap
Matrix6 AdjointMap() const
Definition: Pose3.cpp:69
gtsam::Pose3::y
double y() const
get y
Definition: Pose3.h:296
example2::aTb
Point3 aTb
Definition: testEssentialMatrixFactor.cpp:585
gtsam::Pose3::operator<<
GTSAM_EXPORT friend std::ostream & operator<<(std::ostream &os, const Pose3 &p)
Output stream operator.
Definition: Pose3.cpp:557
Eigen::Triplet< double >
gtsam::Pose3::ChartAtOrigin::Retract
static Pose3 Retract(const Vector6 &xi, ChartJacobian Hxi={})
Definition: Pose3.cpp:272
Eigen::Map
A matrix or vector expression mapping an existing array of data.
Definition: Map.h:94
gtsam::Rot3::inverse
Rot3 inverse() const
inverse of a rotation
Definition: Rot3.h:312
y
Scalar * y
Definition: level1_cplx_impl.h:124
gtsam::so3::DexpFunctor
Definition: SO3.h:165
gtsam::b
const G & b
Definition: Group.h:79
gtsam::Pose3::bearing
Unit3 bearing(const Point3 &point, OptionalJacobian< 2, 6 > Hself={}, OptionalJacobian< 2, 3 > Hpoint={}) const
Definition: Pose3.cpp:460
gtsam::interpolate
T interpolate(const T &X, const T &Y, double t, typename MakeOptionalJacobian< T, T >::type Hx={}, typename MakeOptionalJacobian< T, T >::type Hy={}, typename MakeOptionalJacobian< T, double >::type Ht={})
Definition: Lie.h:363
gtsam::Pose3::ChartAtOrigin::Local
static Vector6 Local(const Pose3 &pose, ChartJacobian Hpose={})
Definition: Pose3.cpp:287
gtsam::Pose3::rotation
const Rot3 & rotation(OptionalJacobian< 3, 6 > Hself={}) const
get rotation
Definition: Pose3.cpp:348
Eigen::Quaternion
The quaternion class used to represent 3D orientations and rotations.
Definition: ForwardDeclarations.h:293
a
ArrayXXi a
Definition: Array_initializer_list_23_cxx11.cpp:1
pose2
Definition: testFrobeniusFactor.cpp:193
gtsam::Pose3::adjoint
static Vector6 adjoint(const Vector6 &xi, const Vector6 &y, OptionalJacobian< 6, 6 > Hxi={}, OptionalJacobian< 6, 6 > H_y={})
Definition: Pose3.cpp:128
gtsam::norm3
double norm3(const Point3 &p, OptionalJacobian< 1, 3 > H)
Distance of the point from the origin, with Jacobian.
Definition: Point3.cpp:41
GTSAM_CONCEPT_POSE_INST
#define GTSAM_CONCEPT_POSE_INST(T)
Definition: geometry/concepts.h:73
gtsam
traits
Definition: SFMdata.h:40
gtsam::traits
Definition: Group.h:36
gtsam::OptionalJacobian
Definition: OptionalJacobian.h:38
gtsam::Pose3::transformFrom
Point3 transformFrom(const Point3 &point, OptionalJacobian< 3, 6 > Hself={}, OptionalJacobian< 3, 3 > Hpoint={}) const
takes point in Pose coordinates and transforms it to world coordinates
Definition: Pose3.cpp:380
p
float * p
Definition: Tutorial_Map_using.cpp:9
G
JacobiRotation< float > G
Definition: Jacobi_makeGivens.cpp:2
v
Array< int, Dynamic, 1 > v
Definition: Array_initializer_list_vector_cxx11.cpp:1
gtsam::Pose3::x
double x() const
get x
Definition: Pose3.h:291
gtsam::Rot3::transpose
Matrix3 transpose() const
Definition: Rot3M.cpp:143
gtsam::Rot3::matrix
Matrix3 matrix() const
Definition: Rot3M.cpp:222
gtsam::tol
const G double tol
Definition: Group.h:79
gtsam::Point3
Vector3 Point3
Definition: Point3.h:38
gtsam::Rot3::Logmap
static Vector3 Logmap(const Rot3 &R, OptionalJacobian< 3, 3 > H={})
Definition: Rot3M.cpp:161
Eigen::Matrix< double, 6, 6 >
gtsam::Unit3
Represents a 3D point on a unit sphere.
Definition: Unit3.h:42
gtsam::LieGroup< Rot3, 3 >::LocalCoordinates
static TangentVector LocalCoordinates(const Rot3 &g)
LocalCoordinates at origin: possible in Lie group because it has an identity.
Definition: Lie.h:116
gtsam::Pose3::adjointMap
static Matrix6 adjointMap(const Vector6 &xi)
Definition: Pose3.cpp:118
align_3::t
Point2 t(10, 10)
gtsam::Hpose2
static const Matrix63 Hpose2
Definition: Pose3.cpp:47
gtsam::Rot3::equals
bool equals(const Rot3 &p, double tol=1e-9) const
Definition: Rot3.cpp:100
Pose3
Definition: testDependencies.h:3
gtsam::Pose3::Align
static std::optional< Pose3 > Align(const Point3Pairs &abPointPairs)
Definition: Pose3.cpp:488
gtsam::Unit3::FromPoint3
static Unit3 FromPoint3(const Point3 &point, OptionalJacobian< 2, 3 > H={})
Named constructor from Point3 with optional Jacobian.
Definition: Unit3.cpp:44
i
int i
Definition: BiCGSTAB_step_by_step.cpp:9
pybind_wrapper_test_script.other
other
Definition: pybind_wrapper_test_script.py:42
R
Rot2 R(Rot2::fromAngle(0.1))
Pose3.h
3D Pose manifold SO(3) x R^3 and group SE(3)
vx
StridedVectorType vx(make_vector(x, *n, std::abs(*incx)))
gtsam::Pose2
Definition: Pose2.h:39
Eigen::Index
EIGEN_DEFAULT_DENSE_INDEX_TYPE Index
The Index type as used for the API.
Definition: Meta.h:74
HR
#define HR
Definition: mincover.c:26
M
Matrix< RealScalar, Dynamic, Dynamic > M
Definition: bench_gemm.cpp:51


gtsam
Author(s):
autogenerated on Fri Apr 25 2025 03:02:34