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/geometry/Pose3.h>
18 #include <gtsam/geometry/Pose2.h>
20 #include <gtsam/base/concepts.h>
21 
22 #include <cmath>
23 #include <iostream>
24 #include <limits>
25 #include <string>
26 
27 namespace gtsam {
28 
29 using std::vector;
30 using Point3Pairs = vector<Point3Pair>;
31 
34 
35 /* ************************************************************************* */
37  R_(Rot3::Rodrigues(0, 0, pose2.theta())), t_(
38  Point3(pose2.x(), pose2.y(), 0)) {
39 }
40 
41 /* ************************************************************************* */
44  if (HR) *HR << I_3x3, Z_3x3;
45  if (Ht) *Ht << Z_3x3, R.transpose();
46  return Pose3(R, t);
47 }
48 
49 /* ************************************************************************* */
51  Rot3 Rt = R_.inverse();
52  return Pose3(Rt, Rt * (-t_));
53 }
54 
55 /* ************************************************************************* */
56 // Calculate Adjoint map
57 // Ad_pose is 6*6 matrix that when applied to twist xi, returns Ad_pose(xi)
58 Matrix6 Pose3::AdjointMap() const {
59  const Matrix3 R = R_.matrix();
60  Matrix3 A = skewSymmetric(t_.x(), t_.y(), t_.z()) * R;
61  Matrix6 adj;
62  adj << R, Z_3x3, A, R;
63  return adj;
64 }
65 
66 /* ************************************************************************* */
67 Matrix6 Pose3::adjointMap(const Vector6& xi) {
68  Matrix3 w_hat = skewSymmetric(xi(0), xi(1), xi(2));
69  Matrix3 v_hat = skewSymmetric(xi(3), xi(4), xi(5));
70  Matrix6 adj;
71  adj << w_hat, Z_3x3, v_hat, w_hat;
72 
73  return adj;
74 }
75 
76 /* ************************************************************************* */
77 Vector6 Pose3::adjoint(const Vector6& xi, const Vector6& y,
79  if (Hxi) {
80  Hxi->setZero();
81  for (int i = 0; i < 6; ++i) {
82  Vector6 dxi;
83  dxi.setZero();
84  dxi(i) = 1.0;
85  Matrix6 Gi = adjointMap(dxi);
86  Hxi->col(i) = Gi * y;
87  }
88  }
89  return adjointMap(xi) * y;
90 }
91 
92 /* ************************************************************************* */
93 Vector6 Pose3::adjointTranspose(const Vector6& xi, const Vector6& y,
95  if (Hxi) {
96  Hxi->setZero();
97  for (int i = 0; i < 6; ++i) {
98  Vector6 dxi;
99  dxi.setZero();
100  dxi(i) = 1.0;
101  Matrix6 GTi = adjointMap(dxi).transpose();
102  Hxi->col(i) = GTi * y;
103  }
104  }
105  return adjointMap(xi).transpose() * y;
106 }
107 
108 /* ************************************************************************* */
109 void Pose3::print(const std::string& s) const {
110  std::cout << (s.empty() ? s : s + " ") << *this << std::endl;
111 }
112 
113 /* ************************************************************************* */
114 bool Pose3::equals(const Pose3& pose, double tol) const {
115  return R_.equals(pose.R_, tol) && traits<Point3>::Equals(t_, pose.t_, tol);
116 }
117 
118 /* ************************************************************************* */
121  if (Hxi) *Hxi = ExpmapDerivative(xi);
122 
123  // get angular velocity omega and translational velocity v from twist xi
124  Vector3 omega(xi(0), xi(1), xi(2)), v(xi(3), xi(4), xi(5));
125 
126  Rot3 R = Rot3::Expmap(omega);
127  double theta2 = omega.dot(omega);
128  if (theta2 > std::numeric_limits<double>::epsilon()) {
129  Vector3 t_parallel = omega * omega.dot(v); // translation parallel to axis
130  Vector3 omega_cross_v = omega.cross(v); // points towards axis
131  Vector3 t = (omega_cross_v - R * omega_cross_v + t_parallel) / theta2;
132  return Pose3(R, t);
133  } else {
134  return Pose3(R, v);
135  }
136 }
137 
138 /* ************************************************************************* */
140  if (Hpose) *Hpose = LogmapDerivative(pose);
141  const Vector3 w = Rot3::Logmap(pose.rotation());
142  const Vector3 T = pose.translation();
143  const double t = w.norm();
144  if (t < 1e-10) {
145  Vector6 log;
146  log << w, T;
147  return log;
148  } else {
149  const Matrix3 W = skewSymmetric(w / t);
150  // Formula from Agrawal06iros, equation (14)
151  // simplified with Mathematica, and multiplying in T to avoid matrix math
152  const double Tan = tan(0.5 * t);
153  const Vector3 WT = W * T;
154  const Vector3 u = T - (0.5 * t) * WT + (1 - t / (2. * Tan)) * (W * WT);
155  Vector6 log;
156  log << w, u;
157  return log;
158  }
159 }
160 
161 /* ************************************************************************* */
163 #ifdef GTSAM_POSE3_EXPMAP
164  return Expmap(xi, Hxi);
165 #else
166  Matrix3 DR;
167  Rot3 R = Rot3::Retract(xi.head<3>(), Hxi ? &DR : 0);
168  if (Hxi) {
169  *Hxi = I_6x6;
170  Hxi->topLeftCorner<3, 3>() = DR;
171  }
172  return Pose3(R, Point3(xi.tail<3>()));
173 #endif
174 }
175 
176 /* ************************************************************************* */
178 #ifdef GTSAM_POSE3_EXPMAP
179  return Logmap(pose, Hpose);
180 #else
181  Matrix3 DR;
182  Vector3 omega = Rot3::LocalCoordinates(pose.rotation(), Hpose ? &DR : 0);
183  if (Hpose) {
184  *Hpose = I_6x6;
185  Hpose->topLeftCorner<3, 3>() = DR;
186  }
187  Vector6 xi;
188  xi << omega, pose.translation();
189  return xi;
190 #endif
191 }
192 
193 /* ************************************************************************* */
194 Matrix3 Pose3::ComputeQforExpmapDerivative(const Vector6& xi, double nearZeroThreshold) {
195  const auto w = xi.head<3>();
196  const auto v = xi.tail<3>();
197  const Matrix3 V = skewSymmetric(v);
198  const Matrix3 W = skewSymmetric(w);
199 
200  Matrix3 Q;
201 
202 #ifdef NUMERICAL_EXPMAP_DERIV
203  Matrix3 Qj = Z_3x3;
204  double invFac = 1.0;
205  Q = Z_3x3;
206  Matrix3 Wj = I_3x3;
207  for (size_t j=1; j<10; ++j) {
208  Qj = Qj*W + Wj*V;
209  invFac = -invFac/(j+1);
210  Q = Q + invFac*Qj;
211  Wj = Wj*W;
212  }
213 #else
214  // The closed-form formula in Barfoot14tro eq. (102)
215  double phi = w.norm();
216  const Matrix3 WVW = W * V * W;
217  if (std::abs(phi) > nearZeroThreshold) {
218  const double s = sin(phi), c = cos(phi);
219  const double phi2 = phi * phi, phi3 = phi2 * phi, phi4 = phi3 * phi,
220  phi5 = phi4 * phi;
221  // Invert the sign of odd-order terms to have the right Jacobian
222  Q = -0.5 * V + (phi - s) / phi3 * (W * V + V * W - WVW) +
223  (1 - phi2 / 2 - c) / phi4 * (W * W * V + V * W * W - 3 * WVW) -
224  0.5 * ((1 - phi2 / 2 - c) / phi4 - 3 * (phi - s - phi3 / 6.) / phi5) *
225  (WVW * W + W * WVW);
226  } else {
227  Q = -0.5 * V + 1. / 6. * (W * V + V * W - WVW) -
228  1. / 24. * (W * W * V + V * W * W - 3 * WVW) +
229  1. / 120. * (WVW * W + W * WVW);
230  }
231 #endif
232 
233  return Q;
234 }
235 
236 /* ************************************************************************* */
237 Matrix6 Pose3::ExpmapDerivative(const Vector6& xi) {
238  const Vector3 w = xi.head<3>();
239  const Matrix3 Jw = Rot3::ExpmapDerivative(w);
240  const Matrix3 Q = ComputeQforExpmapDerivative(xi);
241  Matrix6 J;
242  J << Jw, Z_3x3, Q, Jw;
243  return J;
244 }
245 
246 /* ************************************************************************* */
248  const Vector6 xi = Logmap(pose);
249  const Vector3 w = xi.head<3>();
250  const Matrix3 Jw = Rot3::LogmapDerivative(w);
251  const Matrix3 Q = ComputeQforExpmapDerivative(xi);
252  const Matrix3 Q2 = -Jw*Q*Jw;
253  Matrix6 J;
254  J << Jw, Z_3x3, Q2, Jw;
255  return J;
256 }
257 
258 /* ************************************************************************* */
260  if (Hself) *Hself << Z_3x3, rotation().matrix();
261  return t_;
262 }
263 
264 /* ************************************************************************* */
265 
267  if (Hself) {
268  *Hself << I_3x3, Z_3x3;
269  }
270  return R_;
271 }
272 
273 /* ************************************************************************* */
274 Matrix4 Pose3::matrix() const {
275  static const auto A14 = Eigen::RowVector4d(0,0,0,1);
276  Matrix4 mat;
277  mat << R_.matrix(), t_, A14;
278  return mat;
279 }
280 
281 /* ************************************************************************* */
283  OptionalJacobian<6, 6> HaTb) const {
284  const Pose3& wTa = *this;
285  return wTa.compose(aTb, Hself, HaTb);
286 }
287 
288 /* ************************************************************************* */
290  OptionalJacobian<6, 6> HwTb) const {
291  if (Hself) *Hself = -wTb.inverse().AdjointMap() * AdjointMap();
292  if (HwTb) *HwTb = I_6x6;
293  const Pose3& wTa = *this;
294  return wTa.inverse() * wTb;
295 }
296 
297 /* ************************************************************************* */
299  OptionalJacobian<3, 3> Hpoint) const {
300  // Only get matrix once, to avoid multiple allocations,
301  // as well as multiple conversions in the Quaternion case
302  const Matrix3 R = R_.matrix();
303  if (Hself) {
304  Hself->leftCols<3>() = R * skewSymmetric(-point.x(), -point.y(), -point.z());
305  Hself->rightCols<3>() = R;
306  }
307  if (Hpoint) {
308  *Hpoint = R;
309  }
310  return R_ * point + t_;
311 }
312 
313 /* ************************************************************************* */
315  OptionalJacobian<3, 3> Hpoint) const {
316  // Only get transpose once, to avoid multiple allocations,
317  // as well as multiple conversions in the Quaternion case
318  const Matrix3 Rt = R_.transpose();
319  const Point3 q(Rt*(point - t_));
320  if (Hself) {
321  const double wx = q.x(), wy = q.y(), wz = q.z();
322  (*Hself) <<
323  0.0, -wz, +wy,-1.0, 0.0, 0.0,
324  +wz, 0.0, -wx, 0.0,-1.0, 0.0,
325  -wy, +wx, 0.0, 0.0, 0.0,-1.0;
326  }
327  if (Hpoint) {
328  *Hpoint = Rt;
329  }
330  return q;
331 }
332 
333 /* ************************************************************************* */
335  OptionalJacobian<1, 3> Hpoint) const {
336  Matrix36 D_local_pose;
337  Matrix3 D_local_point;
338  Point3 local = transformTo(point, Hself ? &D_local_pose : 0, Hpoint ? &D_local_point : 0);
339  if (!Hself && !Hpoint) {
340  return local.norm();
341  } else {
342  Matrix13 D_r_local;
343  const double r = norm3(local, D_r_local);
344  if (Hself) *Hself = D_r_local * D_local_pose;
345  if (Hpoint) *Hpoint = D_r_local * D_local_point;
346  return r;
347  }
348 }
349 
350 /* ************************************************************************* */
352  OptionalJacobian<1, 6> Hpose) const {
353  Matrix13 D_local_point;
354  double r = range(pose.translation(), Hself, Hpose ? &D_local_point : 0);
355  if (Hpose) *Hpose << Matrix13::Zero(), D_local_point * pose.rotation().matrix();
356  return r;
357 }
358 
359 /* ************************************************************************* */
361  OptionalJacobian<2, 3> Hpoint) const {
362  Matrix36 D_local_pose;
363  Matrix3 D_local_point;
364  Point3 local = transformTo(point, Hself ? &D_local_pose : 0, Hpoint ? &D_local_point : 0);
365  if (!Hself && !Hpoint) {
366  return Unit3(local);
367  } else {
368  Matrix23 D_b_local;
369  Unit3 b = Unit3::FromPoint3(local, D_b_local);
370  if (Hself) *Hself = D_b_local * D_local_pose;
371  if (Hpoint) *Hpoint = D_b_local * D_local_point;
372  return b;
373  }
374 }
375 
376 /* ************************************************************************* */
378  OptionalJacobian<2, 6> Hpose) const {
379  if (Hpose) {
380  Hpose->setZero();
381  return bearing(pose.translation(), Hself, Hpose.cols<3>(3));
382  }
383  return bearing(pose.translation(), Hself, boost::none);
384 }
385 
386 /* ************************************************************************* */
387 boost::optional<Pose3> Pose3::Align(const Point3Pairs &abPointPairs) {
388  const size_t n = abPointPairs.size();
389  if (n < 3) {
390  return boost::none; // we need at least three pairs
391  }
392 
393  // calculate centroids
394  const auto centroids = means(abPointPairs);
395 
396  // Add to form H matrix
397  Matrix3 H = Z_3x3;
398  for (const Point3Pair &abPair : abPointPairs) {
399  const Point3 da = abPair.first - centroids.first;
400  const Point3 db = abPair.second - centroids.second;
401  H += da * db.transpose();
402  }
403 
404  // ClosestTo finds rotation matrix closest to H in Frobenius sense
405  const Rot3 aRb = Rot3::ClosestTo(H);
406  const Point3 aTb = centroids.first - aRb * centroids.second;
407  return Pose3(aRb, aTb);
408 }
409 
410 boost::optional<Pose3> align(const Point3Pairs &baPointPairs) {
411  Point3Pairs abPointPairs;
412  for (const Point3Pair &baPair : baPointPairs) {
413  abPointPairs.emplace_back(baPair.second, baPair.first);
414  }
415  return Pose3::Align(abPointPairs);
416 }
417 
418 /* ************************************************************************* */
419 std::ostream &operator<<(std::ostream &os, const Pose3& pose) {
420  // Both Rot3 and Point3 have ostream definitions so we use them.
421  os << "R: " << pose.rotation() << "\n";
422  os << "t: " << pose.translation().transpose();
423  return os;
424 }
425 
426 } // namespace gtsam
void print(const std::string &s="") const
print with optional string
Definition: Pose3.cpp:109
static Pose3 Create(const Rot3 &R, const Point3 &t, OptionalJacobian< 6, 3 > HR=boost::none, OptionalJacobian< 6, 3 > Ht=boost::none)
Named constructor with derivatives.
Definition: Pose3.cpp:42
Point3 t_
Translation gPp, from global origin to pose frame origin.
Definition: Pose3.h:47
static Matrix6 adjointMap(const Vector6 &xi)
FIXME Not tested - marked as incorrect.
Definition: Pose3.cpp:67
Unit3 bearing(const Point3 &point, OptionalJacobian< 2, 6 > Hself=boost::none, OptionalJacobian< 2, 3 > Hpoint=boost::none) const
Definition: Pose3.cpp:360
bool equals(const Pose3 &pose, double tol=1e-9) const
assert equality up to a tolerance
Definition: Pose3.cpp:114
Quaternion Q
Scalar * y
Matrix6 AdjointMap() const
Definition: Pose3.cpp:58
Eigen::Vector3d Vector3
Definition: Vector.h:43
ArrayXcf v
Definition: Cwise_arg.cpp:1
Rot3 R_
Rotation gRp, between global and pose frame.
Definition: Pose3.h:46
int n
static Matrix6 LogmapDerivative(const Pose3 &xi)
Derivative of Logmap.
Definition: Pose3.cpp:247
Scalar Scalar * c
Definition: benchVecAdd.cpp:17
Rot2 R(Rot2::fromAngle(0.1))
EIGEN_DEVICE_FUNC const LogReturnType log() const
Key W(std::uint64_t j)
static Vector6 Local(const Pose3 &pose, ChartJacobian Hpose=boost::none)
Definition: Pose3.cpp:177
std::vector< Point3Pair > Point3Pairs
Definition: Point3.h:41
OptionalJacobian< Rows, N > cols(int startCol)
Matrix3 matrix() const
Definition: Rot3M.cpp:219
const Point3 & translation(OptionalJacobian< 3, 6 > Hself=boost::none) const
get translation
Definition: Pose3.cpp:259
GTSAM_CONCEPT_POSE_INST(Pose2)
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
static Matrix6 ExpmapDerivative(const Vector6 &xi)
Derivative of Expmap.
Definition: Pose3.cpp:237
Rot2 theta
static double epsilon
Definition: testRot3.cpp:39
Rot3 inverse() const
inverse of a rotation
Definition: Rot3.h:311
Pose3 transformPoseFrom(const Pose3 &aTb, OptionalJacobian< 6, 6 > Hself=boost::none, OptionalJacobian< 6, 6 > HaTb=boost::none) const
Definition: Pose3.cpp:282
static Vector6 adjointTranspose(const Vector6 &xi, const Vector6 &y, OptionalJacobian< 6, 6 > Hxi=boost::none)
Definition: Pose3.cpp:93
Point3 point(10, 0,-5)
Represents a 3D point on a unit sphere.
Definition: Unit3.h:42
EIGEN_DEVICE_FUNC const CosReturnType cos() const
Point3 transformFrom(const Point3 &point, OptionalJacobian< 3, 6 > Hself=boost::none, OptionalJacobian< 3, 3 > Hpoint=boost::none) const
takes point in Pose coordinates and transforms it to world coordinates
Definition: Pose3.cpp:298
static Matrix3 ComputeQforExpmapDerivative(const Vector6 &xi, double nearZeroThreshold=1e-5)
Definition: Pose3.cpp:194
GTSAM_EXPORT friend std::ostream & operator<<(std::ostream &os, const Pose3 &p)
Output stream operator.
Definition: Pose3.cpp:419
Point3 transformTo(const Point3 &point, OptionalJacobian< 3, 6 > Hself=boost::none, OptionalJacobian< 3, 3 > Hpoint=boost::none) const
takes point in world coordinates and transforms it to Pose coordinates
Definition: Pose3.cpp:314
Class compose(const Class &g) const
Definition: Lie.h:47
Pose3 inverse() const
inverse transformation with derivatives
Definition: Pose3.cpp:50
static Matrix3 LogmapDerivative(const Vector3 &x)
Derivative of Logmap.
Definition: Rot3.cpp:253
SO4 Q2
Definition: testSO4.cpp:55
bool equals(const Rot3 &p, double tol=1e-9) const
Definition: Rot3.cpp:100
static const Pose3 pose(Rot3(Vector3(1,-1,-1).asDiagonal()), Point3(0, 0, 0.5))
Pose3 transformPoseTo(const Pose3 &wTb, OptionalJacobian< 6, 6 > Hself=boost::none, OptionalJacobian< 6, 6 > HwTb=boost::none) const
Definition: Pose3.cpp:289
static Matrix3 ExpmapDerivative(const Vector3 &x)
Derivative of Expmap.
Definition: Rot3.cpp:248
Eigen::Triplet< double > T
double y() const
get y
Definition: Pose3.h:274
double range(const Point3 &point, OptionalJacobian< 1, 6 > Hself=boost::none, OptionalJacobian< 1, 3 > Hpoint=boost::none) const
Definition: Pose3.cpp:334
Array< double, 1, 3 > e(1./3., 0.5, 2.)
RealScalar s
EIGEN_DEVICE_FUNC const Scalar & q
static Vector6 Logmap(const Pose3 &pose, OptionalJacobian< 6, 6 > Hpose=boost::none)
Log map at identity - return the canonical coordinates of this rotation.
Definition: Pose3.cpp:139
EIGEN_DEVICE_FUNC const TanReturnType tan() const
static Rot3 Expmap(const Vector3 &v, OptionalJacobian< 3, 3 > H=boost::none)
Definition: Rot3.h:377
JacobiRotation< float > J
double norm3(const Point3 &p, OptionalJacobian< 1, 3 > H)
Distance of the point from the origin, with Jacobian.
Definition: Point3.cpp:40
const G & b
Definition: Group.h:83
RowVector3d w
Vector xi
Definition: testPose2.cpp:150
Matrix3 transpose() const
Definition: Rot3M.cpp:144
traits
Definition: chartTesting.h:28
boost::optional< Pose2 > align(const vector< Point2Pair > &pairs)
Definition: Pose2.cpp:314
Matrix3 skewSymmetric(double wx, double wy, double wz)
Definition: base/Matrix.h:404
Matrix4 matrix() const
Definition: Pose3.cpp:274
ofstream os("timeSchurFactors.csv")
static Vector3 Logmap(const Rot3 &R, OptionalJacobian< 3, 3 > H=boost::none)
Definition: Rot3M.cpp:158
static TangentVector LocalCoordinates(const Rot3 &g)
LocalCoordinates at origin: possible in Lie group because it has an identity.
Definition: Lie.h:115
The quaternion class used to represent 3D orientations and rotations.
static Vector6 adjoint(const Vector6 &xi, const Vector6 &y, OptionalJacobian< 6, 6 > Hxi=boost::none)
Definition: Pose3.cpp:77
Point3Pair means(const std::vector< Point3Pair > &abPointPairs)
Calculate the two means of a set of Point3 pairs.
Definition: Point3.cpp:78
#define HR
Definition: mincover.c:26
static Rot3 Retract(const TangentVector &v)
Retract at origin: possible in Lie group because it has an identity.
Definition: Lie.h:110
static GTSAM_EXPORT Unit3 FromPoint3(const Point3 &point, OptionalJacobian< 2, 3 > H=boost::none)
Named constructor from Point3 with optional Jacobian.
Definition: Unit3.cpp:36
static Rot3 ClosestTo(const Matrix3 &M)
Definition: Rot3.h:274
static Pose3 Retract(const Vector6 &xi, ChartJacobian Hxi=boost::none)
Definition: Pose3.cpp:162
EIGEN_DEVICE_FUNC const SinReturnType sin() const
const G double tol
Definition: Group.h:83
static const Pose3 pose2
Vector3 Point3
Definition: Point3.h:35
static boost::optional< Pose3 > Align(const std::vector< Point3Pair > &abPointPairs)
Definition: Pose3.cpp:387
2D Pose
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
#define abs(x)
Definition: datatypes.h:17
3D Pose
static Pose3 Expmap(const Vector6 &xi, OptionalJacobian< 6, 6 > Hxi=boost::none)
Exponential map at identity - create a rotation from canonical coordinates .
Definition: Pose3.cpp:120
std::ptrdiff_t j
Point2 t(10, 10)
const Rot3 & rotation(OptionalJacobian< 3, 6 > Hself=boost::none) const
get rotation
Definition: Pose3.cpp:266
std::pair< Point3, Point3 > Point3Pair
Definition: Point3.h:38


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