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)
69 Matrix6 Pose3::AdjointMap() const {
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 void Pose3::print(const std::string& s) const {
165  std::cout << (s.empty() ? s : s + " ") << *this << std::endl;
166 }
167 
168 /* ************************************************************************* */
169 bool Pose3::equals(const Pose3& pose, double tol) const {
170  return R_.equals(pose.R_, tol) && traits<Point3>::Equals(t_, pose.t_, tol);
171 }
172 
173 /* ************************************************************************* */
174 Pose3 Pose3::interpolateRt(const Pose3& T, double t) const {
175  return Pose3(interpolate<Rot3>(R_, T.R_, t),
176  interpolate<Point3>(t_, T.t_, t));
177 }
178 
179 /* ************************************************************************* */
180 // Expmap is implemented in so3::ExpmapFunctor::expmap, based on Ethan Eade's
181 // elegant Lie group document, at https://www.ethaneade.org/lie.pdf.
183  // Get angular velocity omega and translational velocity v from twist xi
184  const Vector3 w = xi.head<3>(), v = xi.tail<3>();
185 
186  // Compute rotation using Expmap
187  Matrix3 Jr;
188  Rot3 R = Rot3::Expmap(w, Hxi ? &Jr : nullptr);
189 
190  // Compute translation and optionally its Jacobian Q in w
191  // The Jacobian in v is the right Jacobian Jr of SO(3), which we already have.
192  Matrix3 Q;
193  const Vector3 t = ExpmapTranslation(w, v, Hxi ? &Q : nullptr);
194 
195  if (Hxi) {
196  *Hxi << Jr, Z_3x3, //
197  Q, Jr;
198  }
199 
200  return Pose3(R, t);
201 }
202 
203 /* ************************************************************************* */
205  if (Hpose) *Hpose = LogmapDerivative(pose);
206  const Vector3 w = Rot3::Logmap(pose.rotation());
207  const Vector3 T = pose.translation();
208  const double t = w.norm();
209  if (t < 1e-10) {
210  Vector6 log;
211  log << w, T;
212  return log;
213  } else {
214  const Matrix3 W = skewSymmetric(w / t);
215  // Formula from Agrawal06iros, equation (14)
216  // simplified with Mathematica, and multiplying in T to avoid matrix math
217  const double Tan = tan(0.5 * t);
218  const Vector3 WT = W * T;
219  const Vector3 u = T - (0.5 * t) * WT + (1 - t / (2. * Tan)) * (W * WT);
220  Vector6 log;
221  log << w, u;
222  return log;
223  }
224 }
225 
226 /* ************************************************************************* */
228 #ifdef GTSAM_POSE3_EXPMAP
229  return Expmap(xi, Hxi);
230 #else
231  Matrix3 DR;
232  Rot3 R = Rot3::Retract(xi.head<3>(), Hxi ? &DR : 0);
233  if (Hxi) {
234  *Hxi = I_6x6;
235  Hxi->topLeftCorner<3, 3>() = DR;
236  }
237  return Pose3(R, Point3(xi.tail<3>()));
238 #endif
239 }
240 
241 /* ************************************************************************* */
243 #ifdef GTSAM_POSE3_EXPMAP
244  return Logmap(pose, Hpose);
245 #else
246  Matrix3 DR;
247  Vector3 omega = Rot3::LocalCoordinates(pose.rotation(), Hpose ? &DR : 0);
248  if (Hpose) {
249  *Hpose = I_6x6;
250  Hpose->topLeftCorner<3, 3>() = DR;
251  }
252  Vector6 xi;
253  xi << omega, pose.translation();
254  return xi;
255 #endif
256 }
257 
258 /* ************************************************************************* */
259 Matrix3 Pose3::ComputeQforExpmapDerivative(const Vector6& xi,
260  double nearZeroThreshold) {
261  const auto w = xi.head<3>();
262  const auto v = xi.tail<3>();
263  Matrix3 Q;
264  ExpmapTranslation(w, v, Q, {}, nearZeroThreshold);
265  return Q;
266 }
267 
268 /* ************************************************************************* */
269 // NOTE(Frank): t = applyLeftJacobian(v) does the same as the intuitive formulas
270 // t_parallel = w * w.dot(v); // translation parallel to axis
271 // w_cross_v = w.cross(v); // translation orthogonal to axis
272 // t = (w_cross_v - Rot3::Expmap(w) * w_cross_v + t_parallel) / theta2;
273 // but functor does not need R, deals automatically with the case where theta2
274 // is near zero, and also gives us the machinery for the Jacobians.
278  double nearZeroThreshold) {
279  const double theta2 = w.dot(w);
280  bool nearZero = (theta2 <= nearZeroThreshold);
281 
282  // Instantiate functor for Dexp-related operations:
283  so3::DexpFunctor local(w, nearZero);
284 
285  // Call applyLeftJacobian which is faster than local.leftJacobian() * v if you
286  // don't need Jacobians, and returns Jacobian of t with respect to w if asked.
287  Matrix3 H;
288  Vector t = local.applyLeftJacobian(v, Q ? &H : nullptr);
289 
290  // We return Jacobians for use in Expmap, so we multiply with X, that
291  // translates from left to right for our right expmap convention:
292  if (Q) {
293  Matrix3 X = local.rightJacobian() * local.leftJacobianInverse();
294  *Q = X * H;
295  }
296 
297  if (J) {
298  *J = local.rightJacobian(); // = X * local.leftJacobian();
299  }
300 
301  return t;
302 }
303 
304 /* ************************************************************************* */
305 Matrix6 Pose3::ExpmapDerivative(const Vector6& xi) {
306  Matrix6 J;
307  Expmap(xi, J);
308  return J;
309 }
310 
311 /* ************************************************************************* */
313  const Vector6 xi = Logmap(pose);
314  const Vector3 w = xi.head<3>();
315  const Matrix3 Jw = Rot3::LogmapDerivative(w);
316  const Matrix3 Q = ComputeQforExpmapDerivative(xi);
317  const Matrix3 Q2 = -Jw*Q*Jw;
318  Matrix6 J;
319  J << Jw, Z_3x3, Q2, Jw;
320  return J;
321 }
322 
323 /* ************************************************************************* */
325  if (Hself) *Hself << Z_3x3, rotation().matrix();
326  return t_;
327 }
328 
329 /* ************************************************************************* */
331  if (Hself) {
332  *Hself << I_3x3, Z_3x3;
333  }
334  return R_;
335 }
336 
337 /* ************************************************************************* */
338 Matrix4 Pose3::matrix() const {
339  static const auto A14 = Eigen::RowVector4d(0,0,0,1);
340  Matrix4 mat;
341  mat << R_.matrix(), t_, A14;
342  return mat;
343 }
344 
345 /* ************************************************************************* */
347  OptionalJacobian<6, 6> HaTb) const {
348  const Pose3& wTa = *this;
349  return wTa.compose(aTb, Hself, HaTb);
350 }
351 
352 /* ************************************************************************* */
354  OptionalJacobian<6, 6> HwTb) const {
355  if (Hself) *Hself = -wTb.inverse().AdjointMap() * AdjointMap();
356  if (HwTb) *HwTb = I_6x6;
357  const Pose3& wTa = *this;
358  return wTa.inverse() * wTb;
359 }
360 
361 /* ************************************************************************* */
363  OptionalJacobian<3, 3> Hpoint) const {
364  // Only get matrix once, to avoid multiple allocations,
365  // as well as multiple conversions in the Quaternion case
366  const Matrix3 R = R_.matrix();
367  if (Hself) {
368  Hself->leftCols<3>() = R * skewSymmetric(-point.x(), -point.y(), -point.z());
369  Hself->rightCols<3>() = R;
370  }
371  if (Hpoint) {
372  *Hpoint = R;
373  }
374  return R_ * point + t_;
375 }
376 
377 Matrix Pose3::transformFrom(const Matrix& points) const {
378  if (points.rows() != 3) {
379  throw std::invalid_argument("Pose3:transformFrom expects 3*N matrix.");
380  }
381  const Matrix3 R = R_.matrix();
382  return (R * points).colwise() + t_; // Eigen broadcasting!
383 }
384 
385 /* ************************************************************************* */
387  OptionalJacobian<3, 3> Hpoint) const {
388  // Only get transpose once, to avoid multiple allocations,
389  // as well as multiple conversions in the Quaternion case
390  const Matrix3 Rt = R_.transpose();
391  const Point3 q(Rt*(point - t_));
392  if (Hself) {
393  const double wx = q.x(), wy = q.y(), wz = q.z();
394  (*Hself) <<
395  0.0, -wz, +wy,-1.0, 0.0, 0.0,
396  +wz, 0.0, -wx, 0.0,-1.0, 0.0,
397  -wy, +wx, 0.0, 0.0, 0.0,-1.0;
398  }
399  if (Hpoint) {
400  *Hpoint = Rt;
401  }
402  return q;
403 }
404 
405 Matrix Pose3::transformTo(const Matrix& points) const {
406  if (points.rows() != 3) {
407  throw std::invalid_argument("Pose3:transformTo expects 3*N matrix.");
408  }
409  const Matrix3 Rt = R_.transpose();
410  return Rt * (points.colwise() - t_); // Eigen broadcasting!
411 }
412 
413 /* ************************************************************************* */
415  OptionalJacobian<1, 3> Hpoint) const {
416  Matrix36 D_local_pose;
417  Matrix3 D_local_point;
418  Point3 local = transformTo(point, Hself ? &D_local_pose : 0, Hpoint ? &D_local_point : 0);
419  if (!Hself && !Hpoint) {
420  return local.norm();
421  } else {
422  Matrix13 D_r_local;
423  const double r = norm3(local, D_r_local);
424  if (Hself) *Hself = D_r_local * D_local_pose;
425  if (Hpoint) *Hpoint = D_r_local * D_local_point;
426  return r;
427  }
428 }
429 
430 /* ************************************************************************* */
432  OptionalJacobian<1, 6> Hpose) const {
433  Matrix13 D_local_point;
434  double r = range(pose.translation(), Hself, Hpose ? &D_local_point : 0);
435  if (Hpose) *Hpose << Matrix13::Zero(), D_local_point * pose.rotation().matrix();
436  return r;
437 }
438 
439 /* ************************************************************************* */
441  OptionalJacobian<2, 3> Hpoint) const {
442  Matrix36 D_local_pose;
443  Matrix3 D_local_point;
444  Point3 local = transformTo(point, Hself ? &D_local_pose : 0, Hpoint ? &D_local_point : 0);
445  if (!Hself && !Hpoint) {
446  return Unit3(local);
447  } else {
448  Matrix23 D_b_local;
449  Unit3 b = Unit3::FromPoint3(local, D_b_local);
450  if (Hself) *Hself = D_b_local * D_local_pose;
451  if (Hpoint) *Hpoint = D_b_local * D_local_point;
452  return b;
453  }
454 }
455 
456 /* ************************************************************************* */
458  OptionalJacobian<2, 6> Hpose) const {
459  if (Hpose) {
460  Hpose->setZero();
461  return bearing(pose.translation(), Hself, Hpose.cols<3>(3));
462  }
463  return bearing(pose.translation(), Hself, {});
464 }
465 
466 /* ************************************************************************* */
467 std::optional<Pose3> Pose3::Align(const Point3Pairs &abPointPairs) {
468  const size_t n = abPointPairs.size();
469  if (n < 3) {
470  return {}; // we need at least three pairs
471  }
472 
473  // calculate centroids
474  const auto centroids = means(abPointPairs);
475 
476  // Add to form H matrix
477  Matrix3 H = Z_3x3;
478  for (const Point3Pair &abPair : abPointPairs) {
479  const Point3 da = abPair.first - centroids.first;
480  const Point3 db = abPair.second - centroids.second;
481  H += da * db.transpose();
482  }
483 
484  // ClosestTo finds rotation matrix closest to H in Frobenius sense
485  const Rot3 aRb = Rot3::ClosestTo(H);
486  const Point3 aTb = centroids.first - aRb * centroids.second;
487  return Pose3(aRb, aTb);
488 }
489 
490 std::optional<Pose3> Pose3::Align(const Matrix& a, const Matrix& b) {
491  if (a.rows() != 3 || b.rows() != 3 || a.cols() != b.cols()) {
492  throw std::invalid_argument(
493  "Pose3:Align expects 3*N matrices of equal shape.");
494  }
495  Point3Pairs abPointPairs;
496  for (Eigen::Index j = 0; j < a.cols(); j++) {
497  abPointPairs.emplace_back(a.col(j), b.col(j));
498  }
499  return Pose3::Align(abPointPairs);
500 }
501 
502 /* ************************************************************************* */
504  return interpolate(*this, other, t, Hx, Hy);
505 }
506 
507 /* ************************************************************************* */
508 std::ostream &operator<<(std::ostream &os, const Pose3& pose) {
509  // Both Rot3 and Point3 have ostream definitions so we use them.
510  os << "R: " << pose.rotation() << "\n";
511  os << "t: " << pose.translation().transpose();
512  return os;
513 }
514 
515 } // 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:503
gtsam::Pose3::interpolateRt
Pose3 interpolateRt(const Pose3 &T, double t) const
Definition: Pose3.cpp:174
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::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::ComputeQforExpmapDerivative
static Matrix3 ComputeQforExpmapDerivative(const Vector6 &xi, double nearZeroThreshold=1e-5)
Definition: Pose3.cpp:259
gtsam::Point3Pairs
std::vector< Point3Pair > Point3Pairs
Definition: Point3.h:45
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:386
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
e
Array< double, 1, 3 > e(1./3., 0.5, 2.)
screwPose2::xi
Vector xi
Definition: testPose2.cpp:148
gtsam::Pose3::FromPose2
static Pose3 FromPose2(const Pose2 &p, OptionalJacobian< 6, 3 > H={})
Definition: Pose3.cpp:55
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:204
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:182
T
Eigen::Triplet< double > T
Definition: Tutorial_sparse_example.cpp:6
gtsam::Matrix
Eigen::MatrixXd Matrix
Definition: base/Matrix.h:39
log
const EIGEN_DEVICE_FUNC LogReturnType log() const
Definition: ArrayCwiseUnaryOps.h:128
simple::pose2
static Pose3 pose2
Definition: testInitializePose3.cpp:58
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:400
Q
Quaternion Q
Definition: testQuaternion.cpp:27
gtsam::Rot3::LogmapDerivative
static Matrix3 LogmapDerivative(const Vector3 &x)
Derivative of Logmap.
Definition: Rot3.cpp:242
gtsam::Pose3::Pose3
Pose3()
Definition: Pose3.h:55
gtsam::Pose3::matrix
Matrix4 matrix() const
Definition: Pose3.cpp:338
gtsam::Pose3::range
double range(const Point3 &point, OptionalJacobian< 1, 6 > Hself={}, OptionalJacobian< 1, 3 > Hpoint={}) const
Definition: Pose3.cpp:414
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:346
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:164
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:353
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:298
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::interpolate
T interpolate(const T &X, const T &Y, double t, typename MakeOptionalJacobian< T, T >::type Hx={}, typename MakeOptionalJacobian< T, T >::type Hy={})
Definition: Lie.h:327
gtsam::Pose3::ExpmapDerivative
static Matrix6 ExpmapDerivative(const Vector6 &xi)
Derivative of Expmap.
Definition: Pose3.cpp:305
gtsam::Pose3::equals
bool equals(const Pose3 &pose, double tol=1e-9) const
assert equality up to a tolerance
Definition: Pose3.cpp:169
gtsam::Pose3::translation
const Point3 & translation(OptionalJacobian< 3, 6 > Hself={}) const
get translation
Definition: Pose3.cpp:324
gtsam::Pose3::AdjointMap
Matrix6 AdjointMap() const
Definition: Pose3.cpp:69
gtsam::Pose3::y
double y() const
get y
Definition: Pose3.h:318
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:508
Eigen::Triplet< double >
tan
const EIGEN_DEVICE_FUNC TanReturnType tan() const
Definition: ArrayCwiseUnaryOps.h:269
gtsam::Pose3::ChartAtOrigin::Retract
static Pose3 Retract(const Vector6 &xi, ChartJacobian Hxi={})
Definition: Pose3.cpp:227
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:162
gtsam::Pose3::ExpmapTranslation
static Vector3 ExpmapTranslation(const Vector3 &w, const Vector3 &v, OptionalJacobian< 3, 3 > Q={}, OptionalJacobian< 3, 3 > J={}, double nearZeroThreshold=1e-5)
Definition: Pose3.cpp:275
Q2
static double Q2[8]
Definition: ndtri.c:122
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:440
gtsam::Pose3::ChartAtOrigin::Local
static Vector6 Local(const Pose3 &pose, ChartJacobian Hpose={})
Definition: Pose3.cpp:242
gtsam::Pose3::rotation
const Rot3 & rotation(OptionalJacobian< 3, 6 > Hself={}) const
get rotation
Definition: Pose3.cpp:330
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
gtsam::OptionalJacobian::cols
OptionalJacobian< Rows, N > cols(int startCol)
Definition: OptionalJacobian.h:172
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::symbol_shorthand::W
Key W(std::uint64_t j)
Definition: inference/Symbol.h:170
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:362
gtsam::Rot3::Expmap
static Rot3 Expmap(const Vector3 &v, OptionalJacobian< 3, 3 > H={})
Definition: Rot3.h:378
p
float * p
Definition: Tutorial_Map_using.cpp:9
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:313
gtsam::Rot3::transpose
Matrix3 transpose() const
Definition: Rot3M.cpp:143
gtsam::Rot3::matrix
Matrix3 matrix() const
Definition: Rot3M.cpp:218
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:157
gtsam::Unit3
Represents a 3D point on a unit sphere.
Definition: Unit3.h:42
gtsam::Pose3::LogmapDerivative
static Matrix6 LogmapDerivative(const Pose3 &xi)
Derivative of Logmap.
Definition: Pose3.cpp:312
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:467
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)
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


gtsam
Author(s):
autogenerated on Tue Jan 7 2025 04:03:31