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 /* ************************************************************************* */
48  Rot3 Rt = R_.inverse();
49  return Pose3(Rt, Rt * (-t_));
50 }
51 
52 /* ************************************************************************* */
53 // Calculate Adjoint map
54 // Ad_pose is 6*6 matrix that when applied to twist xi, returns Ad_pose(xi)
55 Matrix6 Pose3::AdjointMap() const {
56  const Matrix3 R = R_.matrix();
57  Matrix3 A = skewSymmetric(t_.x(), t_.y(), t_.z()) * R;
58  Matrix6 adj;
59  adj << R, Z_3x3, A, R; // Gives [R 0; A R]
60  return adj;
61 }
62 
63 /* ************************************************************************* */
64 // Calculate AdjointMap applied to xi_b, with Jacobians
65 Vector6 Pose3::Adjoint(const Vector6& xi_b, OptionalJacobian<6, 6> H_pose,
66  OptionalJacobian<6, 6> H_xib) const {
67  const Matrix6 Ad = AdjointMap();
68 
69  // Jacobians
70  // D1 Ad_T(xi_b) = D1 Ad_T Ad_I(xi_b) = Ad_T * D1 Ad_I(xi_b) = Ad_T * ad_xi_b
71  // D2 Ad_T(xi_b) = Ad_T
72  // See docs/math.pdf for more details.
73  // In D1 calculation, we could be more efficient by writing it out, but do not
74  // for readability
75  if (H_pose) *H_pose = -Ad * adjointMap(xi_b);
76  if (H_xib) *H_xib = Ad;
77 
78  return Ad * xi_b;
79 }
80 
81 /* ************************************************************************* */
83 Vector6 Pose3::AdjointTranspose(const Vector6& x, OptionalJacobian<6, 6> H_pose,
84  OptionalJacobian<6, 6> H_x) const {
85  const Matrix6 Ad = AdjointMap();
86  const Vector6 AdTx = Ad.transpose() * x;
87 
88  // Jacobians
89  // See docs/math.pdf for more details.
90  if (H_pose) {
91  const auto w_T_hat = skewSymmetric(AdTx.head<3>()),
92  v_T_hat = skewSymmetric(AdTx.tail<3>());
93  *H_pose << w_T_hat, v_T_hat, //
94  /* */ v_T_hat, Z_3x3;
95  }
96  if (H_x) {
97  *H_x = Ad.transpose();
98  }
99 
100  return AdTx;
101 }
102 
103 /* ************************************************************************* */
104 Matrix6 Pose3::adjointMap(const Vector6& xi) {
105  Matrix3 w_hat = skewSymmetric(xi(0), xi(1), xi(2));
106  Matrix3 v_hat = skewSymmetric(xi(3), xi(4), xi(5));
107  Matrix6 adj;
108  adj << w_hat, Z_3x3, v_hat, w_hat;
109 
110  return adj;
111 }
112 
113 /* ************************************************************************* */
114 Vector6 Pose3::adjoint(const Vector6& xi, const Vector6& y,
116  if (Hxi) {
117  Hxi->setZero();
118  for (int i = 0; i < 6; ++i) {
119  Vector6 dxi;
120  dxi.setZero();
121  dxi(i) = 1.0;
122  Matrix6 Gi = adjointMap(dxi);
123  Hxi->col(i) = Gi * y;
124  }
125  }
126  const Matrix6& ad_xi = adjointMap(xi);
127  if (H_y) *H_y = ad_xi;
128  return ad_xi * y;
129 }
130 
131 /* ************************************************************************* */
132 Vector6 Pose3::adjointTranspose(const Vector6& xi, const Vector6& y,
134  if (Hxi) {
135  Hxi->setZero();
136  for (int i = 0; i < 6; ++i) {
137  Vector6 dxi;
138  dxi.setZero();
139  dxi(i) = 1.0;
140  Matrix6 GTi = adjointMap(dxi).transpose();
141  Hxi->col(i) = GTi * y;
142  }
143  }
144  const Matrix6& adT_xi = adjointMap(xi).transpose();
145  if (H_y) *H_y = adT_xi;
146  return adT_xi * y;
147 }
148 
149 /* ************************************************************************* */
150 void Pose3::print(const std::string& s) const {
151  std::cout << (s.empty() ? s : s + " ") << *this << std::endl;
152 }
153 
154 /* ************************************************************************* */
155 bool Pose3::equals(const Pose3& pose, double tol) const {
156  return R_.equals(pose.R_, tol) && traits<Point3>::Equals(t_, pose.t_, tol);
157 }
158 
159 /* ************************************************************************* */
160 Pose3 Pose3::interpolateRt(const Pose3& T, double t) const {
161  return Pose3(interpolate<Rot3>(R_, T.R_, t),
162  interpolate<Point3>(t_, T.t_, t));
163 }
164 
165 /* ************************************************************************* */
166 // Expmap is implemented in so3::ExpmapFunctor::expmap, based on Ethan Eade's
167 // elegant Lie group document, at https://www.ethaneade.org/lie.pdf.
169  // Get angular velocity omega and translational velocity v from twist xi
170  const Vector3 w = xi.head<3>(), v = xi.tail<3>();
171 
172  // Compute rotation using Expmap
173  Matrix3 Jr;
174  Rot3 R = Rot3::Expmap(w, Hxi ? &Jr : nullptr);
175 
176  // Compute translation and optionally its Jacobian Q in w
177  // The Jacobian in v is the right Jacobian Jr of SO(3), which we already have.
178  Matrix3 Q;
179  const Vector3 t = ExpmapTranslation(w, v, Hxi ? &Q : nullptr);
180 
181  if (Hxi) {
182  *Hxi << Jr, Z_3x3, //
183  Q, Jr;
184  }
185 
186  return Pose3(R, t);
187 }
188 
189 /* ************************************************************************* */
191  if (Hpose) *Hpose = LogmapDerivative(pose);
192  const Vector3 w = Rot3::Logmap(pose.rotation());
193  const Vector3 T = pose.translation();
194  const double t = w.norm();
195  if (t < 1e-10) {
196  Vector6 log;
197  log << w, T;
198  return log;
199  } else {
200  const Matrix3 W = skewSymmetric(w / t);
201  // Formula from Agrawal06iros, equation (14)
202  // simplified with Mathematica, and multiplying in T to avoid matrix math
203  const double Tan = tan(0.5 * t);
204  const Vector3 WT = W * T;
205  const Vector3 u = T - (0.5 * t) * WT + (1 - t / (2. * Tan)) * (W * WT);
206  Vector6 log;
207  log << w, u;
208  return log;
209  }
210 }
211 
212 /* ************************************************************************* */
214 #ifdef GTSAM_POSE3_EXPMAP
215  return Expmap(xi, Hxi);
216 #else
217  Matrix3 DR;
218  Rot3 R = Rot3::Retract(xi.head<3>(), Hxi ? &DR : 0);
219  if (Hxi) {
220  *Hxi = I_6x6;
221  Hxi->topLeftCorner<3, 3>() = DR;
222  }
223  return Pose3(R, Point3(xi.tail<3>()));
224 #endif
225 }
226 
227 /* ************************************************************************* */
229 #ifdef GTSAM_POSE3_EXPMAP
230  return Logmap(pose, Hpose);
231 #else
232  Matrix3 DR;
233  Vector3 omega = Rot3::LocalCoordinates(pose.rotation(), Hpose ? &DR : 0);
234  if (Hpose) {
235  *Hpose = I_6x6;
236  Hpose->topLeftCorner<3, 3>() = DR;
237  }
238  Vector6 xi;
239  xi << omega, pose.translation();
240  return xi;
241 #endif
242 }
243 
244 /* ************************************************************************* */
245 Matrix3 Pose3::ComputeQforExpmapDerivative(const Vector6& xi,
246  double nearZeroThreshold) {
247  const auto w = xi.head<3>();
248  const auto v = xi.tail<3>();
249  Matrix3 Q;
250  ExpmapTranslation(w, v, Q, {}, nearZeroThreshold);
251  return Q;
252 }
253 
254 /* ************************************************************************* */
255 // NOTE(Frank): t = applyLeftJacobian(v) does the same as the intuitive formulas
256 // t_parallel = w * w.dot(v); // translation parallel to axis
257 // w_cross_v = w.cross(v); // translation orthogonal to axis
258 // t = (w_cross_v - Rot3::Expmap(w) * w_cross_v + t_parallel) / theta2;
259 // but functor does not need R, deals automatically with the case where theta2
260 // is near zero, and also gives us the machinery for the Jacobians.
264  double nearZeroThreshold) {
265  const double theta2 = w.dot(w);
266  bool nearZero = (theta2 <= nearZeroThreshold);
267 
268  // Instantiate functor for Dexp-related operations:
269  so3::DexpFunctor local(w, nearZero);
270 
271  // Call applyLeftJacobian which is faster than local.leftJacobian() * v if you
272  // don't need Jacobians, and returns Jacobian of t with respect to w if asked.
273  Matrix3 H;
274  Vector t = local.applyLeftJacobian(v, Q ? &H : nullptr);
275 
276  // We return Jacobians for use in Expmap, so we multiply with X, that
277  // translates from left to right for our right expmap convention:
278  if (Q) {
279  Matrix3 X = local.rightJacobian() * local.leftJacobianInverse();
280  *Q = X * H;
281  }
282 
283  if (J) {
284  *J = local.rightJacobian(); // = X * local.leftJacobian();
285  }
286 
287  return t;
288 }
289 
290 /* ************************************************************************* */
291 Matrix6 Pose3::ExpmapDerivative(const Vector6& xi) {
292  Matrix6 J;
293  Expmap(xi, J);
294  return J;
295 }
296 
297 /* ************************************************************************* */
299  const Vector6 xi = Logmap(pose);
300  const Vector3 w = xi.head<3>();
301  const Matrix3 Jw = Rot3::LogmapDerivative(w);
302  const Matrix3 Q = ComputeQforExpmapDerivative(xi);
303  const Matrix3 Q2 = -Jw*Q*Jw;
304  Matrix6 J;
305  J << Jw, Z_3x3, Q2, Jw;
306  return J;
307 }
308 
309 /* ************************************************************************* */
311  if (Hself) *Hself << Z_3x3, rotation().matrix();
312  return t_;
313 }
314 
315 /* ************************************************************************* */
317  if (Hself) {
318  *Hself << I_3x3, Z_3x3;
319  }
320  return R_;
321 }
322 
323 /* ************************************************************************* */
324 Matrix4 Pose3::matrix() const {
325  static const auto A14 = Eigen::RowVector4d(0,0,0,1);
326  Matrix4 mat;
327  mat << R_.matrix(), t_, A14;
328  return mat;
329 }
330 
331 /* ************************************************************************* */
333  OptionalJacobian<6, 6> HaTb) const {
334  const Pose3& wTa = *this;
335  return wTa.compose(aTb, Hself, HaTb);
336 }
337 
338 /* ************************************************************************* */
340  OptionalJacobian<6, 6> HwTb) const {
341  if (Hself) *Hself = -wTb.inverse().AdjointMap() * AdjointMap();
342  if (HwTb) *HwTb = I_6x6;
343  const Pose3& wTa = *this;
344  return wTa.inverse() * wTb;
345 }
346 
347 /* ************************************************************************* */
349  OptionalJacobian<3, 3> Hpoint) const {
350  // Only get matrix once, to avoid multiple allocations,
351  // as well as multiple conversions in the Quaternion case
352  const Matrix3 R = R_.matrix();
353  if (Hself) {
354  Hself->leftCols<3>() = R * skewSymmetric(-point.x(), -point.y(), -point.z());
355  Hself->rightCols<3>() = R;
356  }
357  if (Hpoint) {
358  *Hpoint = R;
359  }
360  return R_ * point + t_;
361 }
362 
363 Matrix Pose3::transformFrom(const Matrix& points) const {
364  if (points.rows() != 3) {
365  throw std::invalid_argument("Pose3:transformFrom expects 3*N matrix.");
366  }
367  const Matrix3 R = R_.matrix();
368  return (R * points).colwise() + t_; // Eigen broadcasting!
369 }
370 
371 /* ************************************************************************* */
373  OptionalJacobian<3, 3> Hpoint) const {
374  // Only get transpose once, to avoid multiple allocations,
375  // as well as multiple conversions in the Quaternion case
376  const Matrix3 Rt = R_.transpose();
377  const Point3 q(Rt*(point - t_));
378  if (Hself) {
379  const double wx = q.x(), wy = q.y(), wz = q.z();
380  (*Hself) <<
381  0.0, -wz, +wy,-1.0, 0.0, 0.0,
382  +wz, 0.0, -wx, 0.0,-1.0, 0.0,
383  -wy, +wx, 0.0, 0.0, 0.0,-1.0;
384  }
385  if (Hpoint) {
386  *Hpoint = Rt;
387  }
388  return q;
389 }
390 
391 Matrix Pose3::transformTo(const Matrix& points) const {
392  if (points.rows() != 3) {
393  throw std::invalid_argument("Pose3:transformTo expects 3*N matrix.");
394  }
395  const Matrix3 Rt = R_.transpose();
396  return Rt * (points.colwise() - t_); // Eigen broadcasting!
397 }
398 
399 /* ************************************************************************* */
401  OptionalJacobian<1, 3> Hpoint) const {
402  Matrix36 D_local_pose;
403  Matrix3 D_local_point;
404  Point3 local = transformTo(point, Hself ? &D_local_pose : 0, Hpoint ? &D_local_point : 0);
405  if (!Hself && !Hpoint) {
406  return local.norm();
407  } else {
408  Matrix13 D_r_local;
409  const double r = norm3(local, D_r_local);
410  if (Hself) *Hself = D_r_local * D_local_pose;
411  if (Hpoint) *Hpoint = D_r_local * D_local_point;
412  return r;
413  }
414 }
415 
416 /* ************************************************************************* */
418  OptionalJacobian<1, 6> Hpose) const {
419  Matrix13 D_local_point;
420  double r = range(pose.translation(), Hself, Hpose ? &D_local_point : 0);
421  if (Hpose) *Hpose << Matrix13::Zero(), D_local_point * pose.rotation().matrix();
422  return r;
423 }
424 
425 /* ************************************************************************* */
427  OptionalJacobian<2, 3> Hpoint) const {
428  Matrix36 D_local_pose;
429  Matrix3 D_local_point;
430  Point3 local = transformTo(point, Hself ? &D_local_pose : 0, Hpoint ? &D_local_point : 0);
431  if (!Hself && !Hpoint) {
432  return Unit3(local);
433  } else {
434  Matrix23 D_b_local;
435  Unit3 b = Unit3::FromPoint3(local, D_b_local);
436  if (Hself) *Hself = D_b_local * D_local_pose;
437  if (Hpoint) *Hpoint = D_b_local * D_local_point;
438  return b;
439  }
440 }
441 
442 /* ************************************************************************* */
444  OptionalJacobian<2, 6> Hpose) const {
445  if (Hpose) {
446  Hpose->setZero();
447  return bearing(pose.translation(), Hself, Hpose.cols<3>(3));
448  }
449  return bearing(pose.translation(), Hself, {});
450 }
451 
452 /* ************************************************************************* */
453 std::optional<Pose3> Pose3::Align(const Point3Pairs &abPointPairs) {
454  const size_t n = abPointPairs.size();
455  if (n < 3) {
456  return {}; // we need at least three pairs
457  }
458 
459  // calculate centroids
460  const auto centroids = means(abPointPairs);
461 
462  // Add to form H matrix
463  Matrix3 H = Z_3x3;
464  for (const Point3Pair &abPair : abPointPairs) {
465  const Point3 da = abPair.first - centroids.first;
466  const Point3 db = abPair.second - centroids.second;
467  H += da * db.transpose();
468  }
469 
470  // ClosestTo finds rotation matrix closest to H in Frobenius sense
471  const Rot3 aRb = Rot3::ClosestTo(H);
472  const Point3 aTb = centroids.first - aRb * centroids.second;
473  return Pose3(aRb, aTb);
474 }
475 
476 std::optional<Pose3> Pose3::Align(const Matrix& a, const Matrix& b) {
477  if (a.rows() != 3 || b.rows() != 3 || a.cols() != b.cols()) {
478  throw std::invalid_argument(
479  "Pose3:Align expects 3*N matrices of equal shape.");
480  }
481  Point3Pairs abPointPairs;
482  for (Eigen::Index j = 0; j < a.cols(); j++) {
483  abPointPairs.emplace_back(a.col(j), b.col(j));
484  }
485  return Pose3::Align(abPointPairs);
486 }
487 
488 /* ************************************************************************* */
490  return interpolate(*this, other, t, Hx, Hy);
491 }
492 
493 /* ************************************************************************* */
494 std::ostream &operator<<(std::ostream &os, const Pose3& pose) {
495  // Both Rot3 and Point3 have ostream definitions so we use them.
496  os << "R: " << pose.rotation() << "\n";
497  os << "t: " << pose.translation().transpose();
498  return os;
499 }
500 
501 } // 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:489
gtsam::Pose3::interpolateRt
Pose3 interpolateRt(const Pose3 &T, double t) const
Definition: Pose3.cpp:160
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:245
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:372
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::adjointTranspose
static Vector6 adjointTranspose(const Vector6 &xi, const Vector6 &y, OptionalJacobian< 6, 6 > Hxi={}, OptionalJacobian< 6, 6 > H_y={})
Definition: Pose3.cpp:132
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:190
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:168
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:324
gtsam::Pose3::range
double range(const Point3 &point, OptionalJacobian< 1, 6 > Hself={}, OptionalJacobian< 1, 3 > Hpoint={}) const
Definition: Pose3.cpp:400
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:332
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:83
gtsam::Pose3::print
void print(const std::string &s="") const
print with optional string
Definition: Pose3.cpp:150
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:339
gtsam::Pose3::Adjoint
Vector6 Adjoint(const Vector6 &xi_b, OptionalJacobian< 6, 6 > H_this={}, OptionalJacobian< 6, 6 > H_xib={}) const
Definition: Pose3.cpp:65
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:47
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:291
gtsam::Pose3::equals
bool equals(const Pose3 &pose, double tol=1e-9) const
assert equality up to a tolerance
Definition: Pose3.cpp:155
gtsam::Pose3::translation
const Point3 & translation(OptionalJacobian< 3, 6 > Hself={}) const
get translation
Definition: Pose3.cpp:310
gtsam::Pose3::AdjointMap
Matrix6 AdjointMap() const
Definition: Pose3.cpp:55
gtsam::Pose3::y
double y() const
get y
Definition: Pose3.h:314
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:494
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:213
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:261
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:426
gtsam::Pose3::ChartAtOrigin::Local
static Vector6 Local(const Pose3 &pose, ChartJacobian Hpose={})
Definition: Pose3.cpp:228
gtsam::Pose3::rotation
const Rot3 & rotation(OptionalJacobian< 3, 6 > Hself={}) const
get rotation
Definition: Pose3.cpp:316
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:114
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:348
gtsam::Rot3::Expmap
static Rot3 Expmap(const Vector3 &v, OptionalJacobian< 3, 3 > H={})
Definition: Rot3.h:378
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:309
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:298
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:104
align_3::t
Point2 t(10, 10)
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:453
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 Sun Dec 22 2024 04:12:45