Go to the documentation of this file.
34 R_(
Rot3::Rodrigues(0, 0,
pose2.theta())), t_(
41 if (
HR) *
HR << I_3x3, Z_3x3;
42 if (Ht) *Ht << Z_3x3,
R.transpose();
47 static const Matrix63
Hpose2 = (Matrix63() <<
53 0., 0., 0.).finished();
73 adj <<
R, Z_3x3,
A,
R;
90 if (H_xib) *H_xib = Ad;
100 const Vector6 AdTx = Ad.transpose() *
x;
107 *H_pose << w_T_hat, v_T_hat,
111 *H_x = Ad.transpose();
122 adj << w_hat, Z_3x3, v_hat, w_hat;
132 for (
int i = 0;
i < 6; ++
i) {
137 Hxi->col(
i) = Gi *
y;
141 if (H_y) *H_y = ad_xi;
150 for (
int i = 0;
i < 6; ++
i) {
155 Hxi->col(
i) = GTi *
y;
159 if (H_y) *H_y = adT_xi;
165 std::cout << (
s.empty() ?
s :
s +
" ") << *
this << std::endl;
175 return Pose3(interpolate<Rot3>(
R_,
T.R_,
t),
176 interpolate<Point3>(
t_,
T.t_,
t));
208 const double t =
w.norm();
217 const double Tan =
tan(0.5 *
t);
219 const Vector3 u =
T - (0.5 *
t) * WT + (1 -
t / (2. * Tan)) * (
W * WT);
228 #ifdef GTSAM_POSE3_EXPMAP
235 Hxi->topLeftCorner<3, 3>() = DR;
243 #ifdef GTSAM_POSE3_EXPMAP
250 Hpose->topLeftCorner<3, 3>() = DR;
260 double nearZeroThreshold) {
261 const auto w =
xi.head<3>();
262 const auto v =
xi.tail<3>();
278 double nearZeroThreshold) {
279 const double theta2 =
w.dot(
w);
280 bool nearZero = (theta2 <= nearZeroThreshold);
288 Vector t = local.applyLeftJacobian(
v,
Q ? &
H :
nullptr);
293 Matrix3
X = local.rightJacobian() * local.leftJacobianInverse();
298 *
J = local.rightJacobian();
317 const Matrix3
Q2 = -Jw*
Q*Jw;
319 J << Jw, Z_3x3,
Q2, Jw;
332 *Hself << I_3x3, Z_3x3;
339 static const auto A14 = Eigen::RowVector4d(0,0,0,1);
348 const Pose3& wTa = *
this;
356 if (HwTb) *HwTb = I_6x6;
357 const Pose3& wTa = *
this;
369 Hself->rightCols<3>() =
R;
378 if (points.rows() != 3) {
379 throw std::invalid_argument(
"Pose3:transformFrom expects 3*N matrix.");
382 return (
R * points).colwise() +
t_;
393 const double wx =
q.x(), wy =
q.y(), wz =
q.z();
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;
406 if (points.rows() != 3) {
407 throw std::invalid_argument(
"Pose3:transformTo expects 3*N matrix.");
410 return Rt * (points.colwise() -
t_);
416 Matrix36 D_local_pose;
417 Matrix3 D_local_point;
419 if (!Hself && !Hpoint) {
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;
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();
442 Matrix36 D_local_pose;
443 Matrix3 D_local_point;
445 if (!Hself && !Hpoint) {
450 if (Hself) *Hself = D_b_local * D_local_pose;
451 if (Hpoint) *Hpoint = D_b_local * D_local_point;
468 const size_t n = abPointPairs.size();
474 const auto centroids =
means(abPointPairs);
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();
486 const Point3 aTb = centroids.first -
aRb * centroids.second;
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.");
497 abPointPairs.emplace_back(
a.col(
j),
b.col(
j));
510 os <<
"R: " <<
pose.rotation() <<
"\n";
511 os <<
"t: " <<
pose.translation().transpose();
Pose3 slerp(double t, const Pose3 &other, OptionalJacobian< 6, 6 > Hx={}, OptionalJacobian< 6, 6 > Hy={}) const
Spherical Linear interpolation between *this and other.
Pose3 interpolateRt(const Pose3 &T, double t) 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 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
std::pair< Point3, Point3 > Point3Pair
Rot3 R_
Rotation gRp, between global and pose frame.
static Matrix3 ComputeQforExpmapDerivative(const Vector6 &xi, double nearZeroThreshold=1e-5)
std::vector< Point3Pair > Point3Pairs
static const Pose3 pose(Rot3(Vector3(1, -1, -1).asDiagonal()), Point3(0, 0, 0.5))
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
Concept-checking macros for geometric objects Each macro instantiates a concept check structure,...
Array< double, 1, 3 > e(1./3., 0.5, 2.)
static Pose3 FromPose2(const Pose2 &p, OptionalJacobian< 6, 3 > H={})
static Vector6 adjointTranspose(const Vector6 &xi, const Vector6 &y, OptionalJacobian< 6, 6 > Hxi={}, OptionalJacobian< 6, 6 > H_y={})
static Rot3 ClosestTo(const Matrix3 &M)
Class compose(const Class &g) const
static Vector6 Logmap(const Pose3 &pose, OptionalJacobian< 6, 6 > Hpose={})
Log map at identity - return the canonical coordinates of this rotation.
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={})
Exponential map at identity - create a rotation from canonical coordinates .
Eigen::Triplet< double > T
const EIGEN_DEVICE_FUNC LogReturnType log() const
ofstream os("timeSchurFactors.csv")
Point3 t_
Translation gPp, from global origin to pose frame origin.
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)
static Matrix3 LogmapDerivative(const Vector3 &x)
Derivative of Logmap.
double range(const Point3 &point, OptionalJacobian< 1, 6 > Hself={}, OptionalJacobian< 1, 3 > Hpoint={}) const
3D rotation represented as a rotation matrix or quaternion
Pose3 transformPoseFrom(const Pose3 &aTb, OptionalJacobian< 6, 6 > Hself={}, OptionalJacobian< 6, 6 > HaTb={}) const
Vector6 AdjointTranspose(const Vector6 &x, OptionalJacobian< 6, 6 > H_this={}, OptionalJacobian< 6, 6 > H_x={}) const
The dual version of Adjoint.
void print(const std::string &s="") const
print with optional string
Pose3 transformPoseTo(const Pose3 &wTb, OptionalJacobian< 6, 6 > Hself={}, OptionalJacobian< 6, 6 > HwTb={}) const
Vector6 Adjoint(const Vector6 &xi_b, OptionalJacobian< 6, 6 > H_this={}, OptionalJacobian< 6, 6 > H_xib={}) const
static Rot3 Retract(const TangentVector &v)
Retract at origin: possible in Lie group because it has an identity.
JacobiRotation< float > J
static Pose3 Create(const Rot3 &R, const Point3 &t, OptionalJacobian< 6, 3 > HR={}, OptionalJacobian< 6, 3 > Ht={})
Named constructor with derivatives.
EIGEN_DEVICE_FUNC const Scalar & q
Rot3 is a 3D rotation represented as a rotation matrix if the preprocessor symbol GTSAM_USE_QUATERNIO...
Pose3 inverse() const
inverse transformation with derivatives
T interpolate(const T &X, const T &Y, double t, typename MakeOptionalJacobian< T, T >::type Hx={}, typename MakeOptionalJacobian< T, T >::type Hy={})
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
const Point3 & translation(OptionalJacobian< 3, 6 > Hself={}) const
get translation
Matrix6 AdjointMap() const
GTSAM_EXPORT friend std::ostream & operator<<(std::ostream &os, const Pose3 &p)
Output stream operator.
const EIGEN_DEVICE_FUNC TanReturnType tan() const
static Pose3 Retract(const Vector6 &xi, ChartJacobian Hxi={})
Rot3 inverse() const
inverse of a rotation
static Vector3 ExpmapTranslation(const Vector3 &w, const Vector3 &v, OptionalJacobian< 3, 3 > Q={}, OptionalJacobian< 3, 3 > J={}, double nearZeroThreshold=1e-5)
Unit3 bearing(const Point3 &point, OptionalJacobian< 2, 6 > Hself={}, OptionalJacobian< 2, 3 > Hpoint={}) const
static Vector6 Local(const Pose3 &pose, ChartJacobian Hpose={})
const Rot3 & rotation(OptionalJacobian< 3, 6 > Hself={}) const
get rotation
The quaternion class used to represent 3D orientations and rotations.
OptionalJacobian< Rows, N > cols(int startCol)
static Vector6 adjoint(const Vector6 &xi, const Vector6 &y, OptionalJacobian< 6, 6 > Hxi={}, OptionalJacobian< 6, 6 > H_y={})
double norm3(const Point3 &p, OptionalJacobian< 1, 3 > H)
Distance of the point from the origin, with Jacobian.
#define GTSAM_CONCEPT_POSE_INST(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
static Rot3 Expmap(const Vector3 &v, OptionalJacobian< 3, 3 > H={})
Array< int, Dynamic, 1 > v
Matrix3 transpose() const
static Vector3 Logmap(const Rot3 &R, OptionalJacobian< 3, 3 > H={})
Represents a 3D point on a unit sphere.
static Matrix6 LogmapDerivative(const Pose3 &xi)
Derivative of Logmap.
static TangentVector LocalCoordinates(const Rot3 &g)
LocalCoordinates at origin: possible in Lie group because it has an identity.
static Matrix6 adjointMap(const Vector6 &xi)
static const Matrix63 Hpose2
bool equals(const Rot3 &p, double tol=1e-9) const
static std::optional< Pose3 > Align(const Point3Pairs &abPointPairs)
static Unit3 FromPoint3(const Point3 &point, OptionalJacobian< 2, 3 > H={})
Named constructor from Point3 with optional Jacobian.
Rot2 R(Rot2::fromAngle(0.1))
3D Pose manifold SO(3) x R^3 and group SE(3)
EIGEN_DEFAULT_DENSE_INDEX_TYPE Index
The Index type as used for the API.
gtsam
Author(s):
autogenerated on Tue Jan 7 2025 04:03:31