36 R_(
Rot3::Rodrigues(0, 0,
pose2.theta())), t_(
43 if (HR) *HR << I_3x3, Z_3x3;
61 adj <<
R, Z_3x3, A,
R;
78 if (H_xib) *H_xib = Ad;
88 const Vector6 AdTx = Ad.transpose() *
x;
95 *H_pose << w_T_hat, v_T_hat,
99 *H_x = Ad.transpose();
110 adj << w_hat, Z_3x3, v_hat, w_hat;
120 for (
int i = 0;
i < 6; ++
i) {
125 Hxi->col(
i) = Gi *
y;
129 if (H_y) *H_y = ad_xi;
138 for (
int i = 0;
i < 6; ++
i) {
143 Hxi->col(
i) = GTi *
y;
146 const Matrix6& adT_xi =
adjointMap(xi).transpose();
147 if (H_y) *H_y = adT_xi;
153 std::cout << (s.empty() ?
s : s +
" ") << *
this << std::endl;
163 return Pose3(interpolate<Rot3>(
R_, T.
R_, t),
164 interpolate<Point3>(
t_, T.
t_, t));
180 Vector3 t = (omega_cross_v - R * omega_cross_v + t_parallel) / theta2;
192 const double t = w.norm();
201 const double Tan =
tan(0.5 * t);
203 const Vector3 u = T - (0.5 *
t) * WT + (1 - t / (2. * Tan)) * (W * WT);
212 #ifdef GTSAM_POSE3_EXPMAP 219 Hxi->topLeftCorner<3, 3>() = DR;
227 #ifdef GTSAM_POSE3_EXPMAP 228 return Logmap(pose, Hpose);
234 Hpose->topLeftCorner<3, 3>() = DR;
244 const auto w = xi.head<3>();
245 const auto v = xi.tail<3>();
251 #ifdef NUMERICAL_EXPMAP_DERIV 256 for (
size_t j=1;
j<10; ++
j) {
258 invFac = -invFac/(
j+1);
264 double phi =
w.norm();
265 const Matrix3 WVW = W * V *
W;
266 if (
std::abs(phi) > nearZeroThreshold) {
267 const double s =
sin(phi),
c =
cos(phi);
268 const double phi2 = phi * phi, phi3 = phi2 * phi, phi4 = phi3 * phi,
271 Q = -0.5 * V + (phi -
s) / phi3 * (W * V + V * W - WVW) +
272 (1 - phi2 / 2 -
c) / phi4 * (W * W * V + V * W * W - 3 * WVW) -
273 0.5 * ((1 - phi2 / 2 -
c) / phi4 - 3 * (phi - s - phi3 / 6.) / phi5) *
276 Q = -0.5 * V + 1. / 6. * (W * V + V * W - WVW) -
277 1. / 24. * (W * W * V + V * W * W - 3 * WVW) +
278 1. / 120. * (WVW * W + W * WVW);
291 J << Jw, Z_3x3,
Q, Jw;
301 const Matrix3
Q2 = -Jw*Q*Jw;
303 J << Jw, Z_3x3,
Q2, Jw;
317 *Hself << I_3x3, Z_3x3;
324 static const auto A14 = Eigen::RowVector4d(0,0,0,1);
333 const Pose3& wTa = *
this;
334 return wTa.
compose(aTb, Hself, HaTb);
341 if (HwTb) *HwTb = I_6x6;
342 const Pose3& wTa = *
this;
353 Hself->leftCols<3>() = R *
skewSymmetric(-point.x(), -point.y(), -point.z());
354 Hself->rightCols<3>() = R;
359 return R_ * point +
t_;
363 if (points.rows() != 3) {
364 throw std::invalid_argument(
"Pose3:transformFrom expects 3*N matrix.");
367 return (R * points).colwise() +
t_;
378 const double wx = q.x(), wy = q.y(), wz = q.z();
380 0.0, -wz, +wy,-1.0, 0.0, 0.0,
381 +wz, 0.0, -wx, 0.0,-1.0, 0.0,
382 -wy, +wx, 0.0, 0.0, 0.0,-1.0;
391 if (points.rows() != 3) {
392 throw std::invalid_argument(
"Pose3:transformTo expects 3*N matrix.");
395 return Rt * (points.colwise() -
t_);
401 Matrix36 D_local_pose;
402 Matrix3 D_local_point;
403 Point3 local =
transformTo(point, Hself ? &D_local_pose : 0, Hpoint ? &D_local_point : 0);
404 if (!Hself && !Hpoint) {
408 const double r =
norm3(local, D_r_local);
409 if (Hself) *Hself = D_r_local * D_local_pose;
410 if (Hpoint) *Hpoint = D_r_local * D_local_point;
418 Matrix13 D_local_point;
420 if (Hpose) *Hpose << Matrix13::Zero(), D_local_point * pose.
rotation().
matrix();
427 Matrix36 D_local_pose;
428 Matrix3 D_local_point;
429 Point3 local =
transformTo(point, Hself ? &D_local_pose : 0, Hpoint ? &D_local_point : 0);
430 if (!Hself && !Hpoint) {
435 if (Hself) *Hself = D_b_local * D_local_pose;
436 if (Hpoint) *Hpoint = D_b_local * D_local_point;
453 const size_t n = abPointPairs.size();
459 const auto centroids =
means(abPointPairs);
463 for (
const Point3Pair &abPair : abPointPairs) {
464 const Point3 da = abPair.first - centroids.first;
465 const Point3 db = abPair.second - centroids.second;
466 H += da * db.transpose();
471 const Point3 aTb = centroids.first - aRb * centroids.second;
472 return Pose3(aRb, aTb);
476 if (a.rows() != 3 || b.rows() != 3 || a.cols() != b.cols()) {
477 throw std::invalid_argument(
478 "Pose3:Align expects 3*N matrices of equal shape.");
482 abPointPairs.emplace_back(a.col(
j), b.col(
j));
495 os <<
"R: " << pose.
rotation() <<
"\n";
static Pose3 Expmap(const Vector6 &xi, OptionalJacobian< 6, 6 > Hxi={})
Exponential map at identity - create a rotation from canonical coordinates .
#define GTSAM_CONCEPT_POSE_INST(T)
Point3 t_
Translation gPp, from global origin to pose frame origin.
static Matrix6 adjointMap(const Vector6 &xi)
Jet< T, N > cos(const Jet< T, N > &f)
const Point3 & translation(OptionalJacobian< 3, 6 > Hself={}) const
get translation
bool equals(const Rot3 &p, double tol=1e-9) const
static Vector6 Logmap(const Pose3 &pose, OptionalJacobian< 6, 6 > Hpose={})
Log map at identity - return the canonical coordinates of this rotation.
Rot3 R_
Rotation gRp, between global and pose frame.
static Matrix6 LogmapDerivative(const Pose3 &xi)
Derivative of Logmap.
Rot2 R(Rot2::fromAngle(0.1))
Jet< T, N > sin(const Jet< T, N > &f)
Pose3 transformPoseFrom(const Pose3 &aTb, OptionalJacobian< 6, 6 > Hself={}, OptionalJacobian< 6, 6 > HaTb={}) const
OptionalJacobian< Rows, N > cols(int startCol)
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.
bool equals(const Pose3 &pose, double tol=1e-9) const
assert equality up to a tolerance
static Vector6 Local(const Pose3 &pose, ChartJacobian Hpose={})
Pose3 slerp(double t, const Pose3 &other, OptionalJacobian< 6, 6 > Hx={}, OptionalJacobian< 6, 6 > Hy={}) const
Spherical Linear interpolation between *this and other.
EIGEN_DEVICE_FUNC const LogReturnType log() const
Rot3 is a 3D rotation represented as a rotation matrix if the preprocessor symbol GTSAM_USE_QUATERNIO...
static Pose3 Retract(const Vector6 &xi, ChartJacobian Hxi={})
static Rot3 Expmap(const Vector3 &v, OptionalJacobian< 3, 3 > H={})
Pose3 inverse() const
inverse transformation with derivatives
Rot3 inverse() const
inverse of a rotation
Represents a 3D point on a unit sphere.
static Matrix3 ComputeQforExpmapDerivative(const Vector6 &xi, double nearZeroThreshold=1e-5)
GTSAM_EXPORT friend std::ostream & operator<<(std::ostream &os, const Pose3 &p)
Output stream operator.
static Matrix3 LogmapDerivative(const Vector3 &x)
Derivative of Logmap.
static Vector3 Logmap(const Rot3 &R, OptionalJacobian< 3, 3 > H={})
static Matrix3 ExpmapDerivative(const Vector3 &x)
Derivative of Expmap.
EIGEN_DEFAULT_DENSE_INDEX_TYPE Index
The Index type as used for the API.
Unit3 bearing(const Point3 &point, OptionalJacobian< 2, 6 > Hself={}, OptionalJacobian< 2, 3 > Hpoint={}) const
Vector6 AdjointTranspose(const Vector6 &x, OptionalJacobian< 6, 6 > H_this={}, OptionalJacobian< 6, 6 > H_x={}) const
The dual version of Adjoint.
Array< int, Dynamic, 1 > v
Eigen::Triplet< double > T
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
Vector::Scalar omega(const Vector &t, const Vector &s, RealScalar angle)
Array< double, 1, 3 > e(1./3., 0.5, 2.)
EIGEN_DEVICE_FUNC const Scalar & q
JacobiRotation< float > J
Class compose(const Class &g) const
static Unit3 FromPoint3(const Point3 &point, OptionalJacobian< 2, 3 > H={})
Named constructor from Point3 with optional Jacobian.
static std::optional< Pose3 > Align(const Point3Pairs &abPointPairs)
Point2Pair means(const std::vector< Point2Pair > &abPointPairs)
Calculate the two means of a set of Point2 pairs.
Matrix3 skewSymmetric(double wx, double wy, double wz)
void print(const std::string &s="") const
print with optional string
static const Pose3 pose(Rot3(Vector3(1, -1, -1).asDiagonal()), Point3(0, 0, 0.5))
ofstream os("timeSchurFactors.csv")
static TangentVector LocalCoordinates(const Rot3 &g)
LocalCoordinates at origin: possible in Lie group because it has an identity.
The quaternion class used to represent 3D orientations and rotations.
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
EIGEN_DEVICE_FUNC const TanReturnType tan() const
static Vector6 adjointTranspose(const Vector6 &xi, const Vector6 &y, OptionalJacobian< 6, 6 > Hxi={}, OptionalJacobian< 6, 6 > H_y={})
static Rot3 Retract(const TangentVector &v)
Retract at origin: possible in Lie group because it has an identity.
static Rot3 ClosestTo(const Matrix3 &M)
const Rot3 & rotation(OptionalJacobian< 3, 6 > Hself={}) const
get rotation
Pose3 interpolateRt(const Pose3 &T, double t) const
double norm3(const Point3 &p, OptionalJacobian< 1, 3 > H)
Distance of the point from the origin, with Jacobian.
Matrix6 AdjointMap() const
Pose3 transformPoseTo(const Pose3 &wTb, OptionalJacobian< 6, 6 > Hself={}, OptionalJacobian< 6, 6 > HwTb={}) const
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
static Pose3 Create(const Rot3 &R, const Point3 &t, OptionalJacobian< 6, 3 > HR={}, OptionalJacobian< 6, 3 > Ht={})
Named constructor with derivatives.
std::vector< Point3Pair > Point3Pairs
T interpolate(const T &X, const T &Y, double t, typename MakeOptionalJacobian< T, T >::type Hx={}, typename MakeOptionalJacobian< T, T >::type Hy={})
static Vector6 adjoint(const Vector6 &xi, const Vector6 &y, OptionalJacobian< 6, 6 > Hxi={}, OptionalJacobian< 6, 6 > H_y={})
Matrix3 transpose() const
Vector6 Adjoint(const Vector6 &xi_b, OptionalJacobian< 6, 6 > H_this={}, OptionalJacobian< 6, 6 > H_xib={}) const
double range(const Point3 &point, OptionalJacobian< 1, 6 > Hself={}, OptionalJacobian< 1, 3 > Hpoint={}) const
std::pair< Point3, Point3 > Point3Pair