Go to the documentation of this file.
34 static const Rot2
R_PI_2(Rot2::fromCosSin(0., 1.));
38 Matrix2
R = r_.matrix();
40 R0.block<2,2>(0,0) =
R;
43 T << t_.x(), t_.y(), 1.0;
45 RT_.block<3,2>(0,0) =
R0;
46 RT_.block<3,1>(0,2) =
T;
52 std::cout << (
s.empty() ?
s :
s +
" ") << *
this << std::endl;
57 os <<
"(" <<
pose.x() <<
", " <<
pose.y() <<
", " <<
pose.theta() <<
")";
62 bool Pose2::equals(
const Pose2&
q,
double tol)
const {
68 assert(
xi.size() == 3);
69 if (
H) *
H = Pose2::ExpmapDerivative(
xi);
71 const double w =
xi(2);
75 const Rot2 R(Rot2::fromAngle(
w));
77 const Point2 t = (v_ortho -
R.rotate(v_ortho)) /
w;
84 if (
H) *
H = Pose2::LogmapDerivative(
p);
91 double c_1 =
R.c()-1.0,
s =
R.s();
92 double det = c_1*c_1 +
s*
s;
101 #ifdef GTSAM_SLOW_BUT_CORRECT_EXPMAP
113 #ifdef GTSAM_SLOW_BUT_CORRECT_EXPMAP
127 Matrix3 Pose2::AdjointMap()
const {
128 double c = r_.c(),
s = r_.s(),
x = t_.x(),
y = t_.y();
149 Matrix3 Pose2::ExpmapDerivative(
const Vector3&
v) {
164 J << sZalpha, -c_1Zalpha, v1Zalpha + v2Zalpha*c_1Zalpha - v1Zalpha*sZalpha,
165 c_1Zalpha, sZalpha, -v1Zalpha*c_1Zalpha + v2Zalpha - v2Zalpha*sZalpha,
180 Matrix3 Pose2::LogmapDerivative(
const Pose2&
p) {
185 double alphaInv = 1/
alpha;
187 double v1 =
v[0],
v2 =
v[1];
189 J <<
alpha*halfCotHalfAlpha, -0.5*
alpha,
v1*alphaInv -
v1*halfCotHalfAlpha + 0.5*
v2,
190 0.5*
alpha,
alpha*halfCotHalfAlpha,
v2*alphaInv - 0.5*
v1 -
v2*halfCotHalfAlpha,
203 return Pose2(r_.inverse(), r_.unrotate(
Point2(-t_.x(), -t_.y())));
212 const Point2 q = r_.unrotate(
point - t_, Hrotation, Hpoint);
213 if (Htranslation) *Htranslation << -1.0, 0.0, 0.0, -1.0;
218 if (points.rows() != 2) {
219 throw std::invalid_argument(
"Pose2:transformTo expects 2*N matrix.");
222 return Rt * (points.colwise() - t_);
232 if (Htranslation) *Htranslation = (Hpoint ? *Hpoint : r_.matrix());
238 if (points.rows() != 2) {
239 throw std::invalid_argument(
"Pose2:transformFrom expects 2*N matrix.");
242 return (
R * points).colwise() + t_;
249 Matrix23 D_d_pose; Matrix2 D_d_point;
251 if (!Hpose && !Hpoint)
return Rot2::relativeBearing(
d);
253 Rot2 result = Rot2::relativeBearing(
d, Hpose || Hpoint ? &D_result_d : 0);
254 if (Hpose) *Hpose = D_result_d * D_d_pose;
255 if (Hpoint) *Hpoint = D_result_d * D_d_point;
265 Matrix12 H2_ = D2 *
pose.r().matrix();
266 *Hother << H2_, Z_1x1;
274 if (!Hpose && !Hpoint)
return d.norm();
276 double r =
norm2(
d, D_r_d);
279 D_d_pose << -r_.c(), r_.s(), 0.0,
280 -r_.s(), -r_.c(), 0.0;
281 *Hpose = D_r_d * D_d_pose;
283 if (Hpoint) *Hpoint = D_r_d;
292 if (!Hpose && !Hother)
return d.norm();
294 double r =
norm2(
d, D_r_d);
298 -r_.c(), r_.s(), 0.0,
299 -r_.s(), -r_.c(), 0.0;
300 *Hpose = D_r_d * D_d_pose;
307 *Hother = D_r_d * D_d_other;
332 const size_t n = ab_pairs.size();
338 Point2 ca(0, 0), cb(0, 0);
343 const double f = 1.0/
n;
350 Point2 da = pair.first - ca;
351 Point2 db = pair.second - cb;
352 c += db.x() * da.x() + db.y() * da.y();
353 s += -db.y() * da.x() + db.x() * da.y();
357 const double theta =
atan2(
s,
c);
358 const Rot2 R = Rot2::fromAngle(theta);
364 if (
a.rows() != 2 ||
b.rows() != 2 ||
a.cols() !=
b.cols()) {
365 throw std::invalid_argument(
366 "Pose2:Align expects 2*N matrices of equal shape.");
370 ab_pairs.emplace_back(
a.col(
j),
b.col(
j));
Rot3 rotation(const Pose3 &pose, OptionalJacobian< 3, 6 > 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
EIGEN_STRONG_INLINE Packet4f print(const Packet4f &a)
static const Pose3 pose(Rot3(Vector3(1, -1, -1).asDiagonal()), Point3(0, 0, 0.5))
const EIGEN_DEVICE_FUNC InverseReturnType inverse() const
Concept-checking macros for geometric objects Each macro instantiates a concept check structure,...
Array< double, 1, 3 > e(1./3., 0.5, 2.)
static const double d[K][N]
Concept check for values that can be used in unit tests.
Jet< T, N > sin(const Jet< T, N > &f)
const Rot2 & rotation(OptionalJacobian< 1, 3 > Hself={}) const
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
bool equal_with_abs_tol(const Eigen::DenseBase< MATRIX > &A, const Eigen::DenseBase< MATRIX > &B, double tol=1e-9)
Eigen::Triplet< double > T
ofstream os("timeSchurFactors.csv")
Jet< T, N > cos(const Jet< T, N > &f)
std::pair< Point2, Point2 > Point2Pair
Double_ range(const Point2_ &p, const Point2_ &q)
Pose2_ Expmap(const Vector3_ &xi)
Point3_ transformFrom(const Pose3_ &x, const Point3_ &p)
JacobiRotation< float > J
Line3 transformTo(const Pose3 &wTc, const Line3 &wL, OptionalJacobian< 4, 6 > Dpose, OptionalJacobian< 4, 4 > Dline)
EIGEN_DEVICE_FUNC const Scalar & q
Map< Matrix< T, Dynamic, Dynamic, ColMajor >, 0, OuterStride<> > matrix(T *data, int rows, int cols, int stride)
double theta() const
get theta
AnnoyingScalar atan2(const AnnoyingScalar &y, const AnnoyingScalar &x)
Point2(* f)(const Point3 &, OptionalJacobian< 2, 3 >)
OptionalJacobian< Rows, N > cols(int startCol)
#define GTSAM_CONCEPT_POSE_INST(T)
std::ostream & operator<<(std::ostream &os, const Pose2 &pose)
Array< int, Dynamic, 1 > v
Matrix3 transpose() const
static const Rot2 R_PI_2(Rot2::fromCosSin(0., 1.))
std::vector< Point2Pair > Point2Pairs
static Similarity2 Align(const Point2Pairs &d_abPointPairs, const Rot2 &aRb, const Point2Pair ¢roids)
This method estimates the similarity transform from differences point pairs, given a known or estimat...
double norm2(const Point2 &p, OptionalJacobian< 1, 2 > H)
Distance of the point from the origin, with Jacobian.
Rot2 R(Rot2::fromAngle(0.1))
EIGEN_DEFAULT_DENSE_INDEX_TYPE Index
The Index type as used for the API.
gtsam
Author(s):
autogenerated on Sun Dec 22 2024 04:12:45