37 R_(
Rot3::Rodrigues(0, 0, pose2.
theta())), t_(
44 if (HR) *HR << I_3x3, Z_3x3;
62 adj <<
R, Z_3x3, A,
R;
71 adj << w_hat, Z_3x3, v_hat, w_hat;
81 for (
int i = 0;
i < 6; ++
i) {
97 for (
int i = 0;
i < 6; ++
i) {
102 Hxi->col(
i) = GTi *
y;
110 std::cout << (s.empty() ? s : s +
" ") << *
this << std::endl;
127 double theta2 = omega.dot(omega);
129 Vector3 t_parallel = omega * omega.dot(v);
130 Vector3 omega_cross_v = omega.cross(v);
131 Vector3 t = (omega_cross_v - R * omega_cross_v + t_parallel) / theta2;
143 const double t = w.norm();
152 const double Tan =
tan(0.5 * t);
154 const Vector3 u = T - (0.5 *
t) * WT + (1 - t / (2. * Tan)) * (W * WT);
163 #ifdef GTSAM_POSE3_EXPMAP 170 Hxi->topLeftCorner<3, 3>() = DR;
178 #ifdef GTSAM_POSE3_EXPMAP 179 return Logmap(pose, Hpose);
185 Hpose->topLeftCorner<3, 3>() = DR;
195 const auto w = xi.head<3>();
196 const auto v = xi.tail<3>();
202 #ifdef NUMERICAL_EXPMAP_DERIV 207 for (
size_t j=1;
j<10; ++
j) {
209 invFac = -invFac/(
j+1);
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,
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) *
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);
242 J << Jw, Z_3x3,
Q, Jw;
252 const Matrix3
Q2 = -Jw*Q*Jw;
254 J << Jw, Z_3x3,
Q2, Jw;
268 *Hself << I_3x3, Z_3x3;
275 static const auto A14 = Eigen::RowVector4d(0,0,0,1);
284 const Pose3& wTa = *
this;
285 return wTa.
compose(aTb, Hself, HaTb);
292 if (HwTb) *HwTb = I_6x6;
293 const Pose3& wTa = *
this;
304 Hself->leftCols<3>() = R *
skewSymmetric(-point.x(), -point.y(), -point.z());
305 Hself->rightCols<3>() = R;
310 return R_ * point +
t_;
321 const double wx = q.x(), wy = q.y(), wz = q.z();
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;
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) {
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;
353 Matrix13 D_local_point;
355 if (Hpose) *Hpose << Matrix13::Zero(), D_local_point * pose.
rotation().
matrix();
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) {
370 if (Hself) *Hself = D_b_local * D_local_pose;
371 if (Hpoint) *Hpoint = D_b_local * D_local_point;
388 const size_t n = abPointPairs.size();
394 const auto centroids =
means(abPointPairs);
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();
406 const Point3 aTb = centroids.first - aRb * centroids.second;
407 return Pose3(aRb, aTb);
412 for (
const Point3Pair &baPair : baPointPairs) {
413 abPointPairs.emplace_back(baPair.second, baPair.first);
421 os <<
"R: " << pose.
rotation() <<
"\n";
void print(const std::string &s="") const
print with optional string
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.
Point3 t_
Translation gPp, from global origin to pose frame origin.
static Matrix6 adjointMap(const Vector6 &xi)
FIXME Not tested - marked as incorrect.
Unit3 bearing(const Point3 &point, OptionalJacobian< 2, 6 > Hself=boost::none, OptionalJacobian< 2, 3 > Hpoint=boost::none) const
bool equals(const Pose3 &pose, double tol=1e-9) const
assert equality up to a tolerance
Matrix6 AdjointMap() const
Rot3 R_
Rotation gRp, between global and pose frame.
static Matrix6 LogmapDerivative(const Pose3 &xi)
Derivative of Logmap.
Rot2 R(Rot2::fromAngle(0.1))
EIGEN_DEVICE_FUNC const LogReturnType log() const
static Vector6 Local(const Pose3 &pose, ChartJacobian Hpose=boost::none)
std::vector< Point3Pair > Point3Pairs
OptionalJacobian< Rows, N > cols(int startCol)
const Point3 & translation(OptionalJacobian< 3, 6 > Hself=boost::none) const
get translation
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.
Rot3 inverse() const
inverse of a rotation
Pose3 transformPoseFrom(const Pose3 &aTb, OptionalJacobian< 6, 6 > Hself=boost::none, OptionalJacobian< 6, 6 > HaTb=boost::none) const
static Vector6 adjointTranspose(const Vector6 &xi, const Vector6 &y, OptionalJacobian< 6, 6 > Hxi=boost::none)
Represents a 3D point on a unit sphere.
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
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.
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
Class compose(const Class &g) const
Pose3 inverse() const
inverse transformation with derivatives
static Matrix3 LogmapDerivative(const Vector3 &x)
Derivative of Logmap.
bool equals(const Rot3 &p, double tol=1e-9) const
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
static Matrix3 ExpmapDerivative(const Vector3 &x)
Derivative of Expmap.
Eigen::Triplet< double > T
double range(const Point3 &point, OptionalJacobian< 1, 6 > Hself=boost::none, OptionalJacobian< 1, 3 > Hpoint=boost::none) const
Array< double, 1, 3 > e(1./3., 0.5, 2.)
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.
EIGEN_DEVICE_FUNC const TanReturnType tan() const
static Rot3 Expmap(const Vector3 &v, OptionalJacobian< 3, 3 > H=boost::none)
JacobiRotation< float > J
double norm3(const Point3 &p, OptionalJacobian< 1, 3 > H)
Distance of the point from the origin, with Jacobian.
Matrix3 transpose() const
boost::optional< Pose2 > align(const vector< Point2Pair > &pairs)
Matrix3 skewSymmetric(double wx, double wy, double wz)
ofstream os("timeSchurFactors.csv")
static Vector3 Logmap(const Rot3 &R, OptionalJacobian< 3, 3 > H=boost::none)
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.
static Vector6 adjoint(const Vector6 &xi, const Vector6 &y, OptionalJacobian< 6, 6 > Hxi=boost::none)
Point3Pair means(const std::vector< Point3Pair > &abPointPairs)
Calculate the two means of a set of Point3 pairs.
static Rot3 Retract(const TangentVector &v)
Retract at origin: possible in Lie group because it has an identity.
static GTSAM_EXPORT Unit3 FromPoint3(const Point3 &point, OptionalJacobian< 2, 3 > H=boost::none)
Named constructor from Point3 with optional Jacobian.
static Rot3 ClosestTo(const Matrix3 &M)
static Pose3 Retract(const Vector6 &xi, ChartJacobian Hxi=boost::none)
EIGEN_DEVICE_FUNC const SinReturnType sin() const
static boost::optional< Pose3 > Align(const std::vector< Point3Pair > &abPointPairs)
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 Expmap(const Vector6 &xi, OptionalJacobian< 6, 6 > Hxi=boost::none)
Exponential map at identity - create a rotation from canonical coordinates .
const Rot3 & rotation(OptionalJacobian< 3, 6 > Hself=boost::none) const
get rotation
std::pair< Point3, Point3 > Point3Pair