Pose2.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 
18 #include <gtsam/geometry/Pose2.h>
19 #include <gtsam/base/Testable.h>
20 #include <gtsam/base/concepts.h>
21 
22 #include <cmath>
23 #include <cassert>
24 #include <iostream>
25 #include <iomanip>
26 
27 using namespace std;
28 
29 namespace gtsam {
30 
33 
34 static const Rot2 R_PI_2(Rot2::fromCosSin(0., 1.));
35 
36 /* ************************************************************************* */
37 Matrix3 Pose2::matrix() const {
38  Matrix2 R = r_.matrix();
39  Matrix32 R0;
40  R0.block<2,2>(0,0) = R;
41  R0.block<1,2>(2,0).setZero();
42  Matrix31 T;
43  T << t_.x(), t_.y(), 1.0;
44  Matrix3 RT_;
45  RT_.block<3,2>(0,0) = R0;
46  RT_.block<3,1>(0,2) = T;
47  return RT_;
48 }
49 
50 /* ************************************************************************* */
51 void Pose2::print(const string& s) const {
52  std::cout << (s.empty() ? s : s + " ") << *this << std::endl;
53 }
54 
55 /* ************************************************************************* */
56 std::ostream &operator<<(std::ostream &os, const Pose2& pose) {
57  os << "(" << pose.x() << ", " << pose.y() << ", " << pose.theta() << ")";
58  return os;
59 }
60 
61 /* ************************************************************************* */
62 bool Pose2::equals(const Pose2& q, double tol) const {
63  return equal_with_abs_tol(t_, q.t_, tol) && r_.equals(q.r_, tol);
64 }
65 
66 /* ************************************************************************* */
68  assert(xi.size() == 3);
69  if (H) *H = Pose2::ExpmapDerivative(xi);
70  const Point2 v(xi(0),xi(1));
71  const double w = xi(2);
72  if (std::abs(w) < 1e-10)
73  return Pose2(xi[0], xi[1], xi[2]);
74  else {
75  const Rot2 R(Rot2::fromAngle(w));
76  const Point2 v_ortho = R_PI_2 * v; // points towards rot center
77  const Point2 t = (v_ortho - R.rotate(v_ortho)) / w;
78  return Pose2(R, t);
79  }
80 }
81 
82 /* ************************************************************************* */
83 Vector3 Pose2::Logmap(const Pose2& p, OptionalJacobian<3, 3> H) {
84  if (H) *H = Pose2::LogmapDerivative(p);
85  const Rot2& R = p.r();
86  const Point2& t = p.t();
87  double w = R.theta();
88  if (std::abs(w) < 1e-10)
89  return Vector3(t.x(), t.y(), w);
90  else {
91  double c_1 = R.c()-1.0, s = R.s();
92  double det = c_1*c_1 + s*s;
93  Point2 p = R_PI_2 * (R.unrotate(t) - t);
94  Point2 v = (w/det) * p;
95  return Vector3(v.x(), v.y(), w);
96  }
97 }
98 
99 /* ************************************************************************* */
100 Pose2 Pose2::ChartAtOrigin::Retract(const Vector3& v, ChartJacobian H) {
101 #ifdef GTSAM_SLOW_BUT_CORRECT_EXPMAP
102  return Expmap(v, H);
103 #else
104  if (H) {
105  *H = I_3x3;
106  H->topLeftCorner<2,2>() = Rot2(-v[2]).matrix();
107  }
108  return Pose2(v[0], v[1], v[2]);
109 #endif
110 }
111 /* ************************************************************************* */
112 Vector3 Pose2::ChartAtOrigin::Local(const Pose2& r, ChartJacobian H) {
113 #ifdef GTSAM_SLOW_BUT_CORRECT_EXPMAP
114  return Logmap(r, H);
115 #else
116  if (H) {
117  *H = I_3x3;
118  H->topLeftCorner<2,2>() = r.rotation().matrix();
119  }
120  return Vector3(r.x(), r.y(), r.theta());
121 #endif
122 }
123 
124 /* ************************************************************************* */
125 // Calculate Adjoint map
126 // Ad_pose is 3*3 matrix that when applied to twist xi, returns Ad_pose(xi)
127 Matrix3 Pose2::AdjointMap() const {
128  double c = r_.c(), s = r_.s(), x = t_.x(), y = t_.y();
129  Matrix3 rvalue;
130  rvalue <<
131  c, -s, y,
132  s, c, -x,
133  0.0, 0.0, 1.0;
134  return rvalue;
135 }
136 
137 /* ************************************************************************* */
138 Matrix3 Pose2::adjointMap(const Vector3& v) {
139  // See Chirikjian12book2, vol.2, pg. 36
140  Matrix3 ad = Z_3x3;
141  ad(0,1) = -v[2];
142  ad(1,0) = v[2];
143  ad(0,2) = v[1];
144  ad(1,2) = -v[0];
145  return ad;
146 }
147 
148 /* ************************************************************************* */
149 Matrix3 Pose2::ExpmapDerivative(const Vector3& v) {
150  double alpha = v[2];
151  Matrix3 J;
152  if (std::abs(alpha) > 1e-5) {
153  // Chirikjian11book2, pg. 36
154  /* !!!Warning!!! Compare Iserles05an, formula 2.42 and Chirikjian11book2 pg.26
155  * Iserles' right-trivialization dexpR is actually the left Jacobian J_l in Chirikjian's notation
156  * In fact, Iserles 2.42 can be written as:
157  * \dot{g} g^{-1} = dexpR_{q}\dot{q}
158  * where q = A, and g = exp(A)
159  * and the LHS is in the definition of J_l in Chirikjian11book2, pg. 26.
160  * Hence, to compute ExpmapDerivative, we have to use the formula of J_r Chirikjian11book2, pg.36
161  */
162  double sZalpha = sin(alpha)/alpha, c_1Zalpha = (cos(alpha)-1)/alpha;
163  double v1Zalpha = v[0]/alpha, v2Zalpha = v[1]/alpha;
164  J << sZalpha, -c_1Zalpha, v1Zalpha + v2Zalpha*c_1Zalpha - v1Zalpha*sZalpha,
165  c_1Zalpha, sZalpha, -v1Zalpha*c_1Zalpha + v2Zalpha - v2Zalpha*sZalpha,
166  0, 0, 1;
167  }
168  else {
169  // Thanks to Krunal: Apply L'Hospital rule to several times to
170  // compute the limits when alpha -> 0
171  J << 1,0,-0.5*v[1],
172  0,1, 0.5*v[0],
173  0,0, 1;
174  }
175 
176  return J;
177 }
178 
179 /* ************************************************************************* */
180 Matrix3 Pose2::LogmapDerivative(const Pose2& p) {
181  Vector3 v = Logmap(p);
182  double alpha = v[2];
183  Matrix3 J;
184  if (std::abs(alpha) > 1e-5) {
185  double alphaInv = 1/alpha;
186  double halfCotHalfAlpha = 0.5*sin(alpha)/(1-cos(alpha));
187  double v1 = v[0], v2 = v[1];
188 
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,
191  0, 0, 1;
192  }
193  else {
194  J << 1,0, 0.5*v[1],
195  0,1, -0.5*v[0],
196  0,0, 1;
197  }
198  return J;
199 }
200 
201 /* ************************************************************************* */
203  return Pose2(r_.inverse(), r_.unrotate(Point2(-t_.x(), -t_.y())));
204 }
205 
206 /* ************************************************************************* */
207 // see doc/math.lyx, SE(2) section
209  OptionalJacobian<2, 3> Hpose, OptionalJacobian<2, 2> Hpoint) const {
210  OptionalJacobian<2, 2> Htranslation = Hpose.cols<2>(0);
211  OptionalJacobian<2, 1> Hrotation = Hpose.cols<1>(2);
212  const Point2 q = r_.unrotate(point - t_, Hrotation, Hpoint);
213  if (Htranslation) *Htranslation << -1.0, 0.0, 0.0, -1.0;
214  return q;
215 }
216 
217 Matrix Pose2::transformTo(const Matrix& points) const {
218  if (points.rows() != 2) {
219  throw std::invalid_argument("Pose2:transformTo expects 2*N matrix.");
220  }
221  const Matrix2 Rt = rotation().transpose();
222  return Rt * (points.colwise() - t_); // Eigen broadcasting!
223 }
224 
225 /* ************************************************************************* */
226 // see doc/math.lyx, SE(2) section
228  OptionalJacobian<2, 3> Hpose, OptionalJacobian<2, 2> Hpoint) const {
229  OptionalJacobian<2, 2> Htranslation = Hpose.cols<2>(0);
230  OptionalJacobian<2, 1> Hrotation = Hpose.cols<1>(2);
231  const Point2 q = r_.rotate(point, Hrotation, Hpoint);
232  if (Htranslation) *Htranslation = (Hpoint ? *Hpoint : r_.matrix());
233  return q + t_;
234 }
235 
236 
237 Matrix Pose2::transformFrom(const Matrix& points) const {
238  if (points.rows() != 2) {
239  throw std::invalid_argument("Pose2:transformFrom expects 2*N matrix.");
240  }
241  const Matrix2 R = rotation().matrix();
242  return (R * points).colwise() + t_; // Eigen broadcasting!
243 }
244 
245 /* ************************************************************************* */
246 Rot2 Pose2::bearing(const Point2& point,
247  OptionalJacobian<1, 3> Hpose, OptionalJacobian<1, 2> Hpoint) const {
248  // make temporary matrices
249  Matrix23 D_d_pose; Matrix2 D_d_point;
250  Point2 d = transformTo(point, Hpose ? &D_d_pose : 0, Hpoint ? &D_d_point : 0);
251  if (!Hpose && !Hpoint) return Rot2::relativeBearing(d);
252  Matrix12 D_result_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;
256  return result;
257 }
258 
259 /* ************************************************************************* */
260 Rot2 Pose2::bearing(const Pose2& pose,
261  OptionalJacobian<1, 3> Hpose, OptionalJacobian<1, 3> Hother) const {
262  Matrix12 D2;
263  Rot2 result = bearing(pose.t(), Hpose, Hother ? &D2 : 0);
264  if (Hother) {
265  Matrix12 H2_ = D2 * pose.r().matrix();
266  *Hother << H2_, Z_1x1;
267  }
268  return result;
269 }
270 /* ************************************************************************* */
271 double Pose2::range(const Point2& point,
272  OptionalJacobian<1,3> Hpose, OptionalJacobian<1,2> Hpoint) const {
273  Point2 d = point - t_;
274  if (!Hpose && !Hpoint) return d.norm();
275  Matrix12 D_r_d;
276  double r = norm2(d, D_r_d);
277  if (Hpose) {
278  Matrix23 D_d_pose;
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;
282  }
283  if (Hpoint) *Hpoint = D_r_d;
284  return r;
285 }
286 
287 /* ************************************************************************* */
288 double Pose2::range(const Pose2& pose,
289  OptionalJacobian<1,3> Hpose,
290  OptionalJacobian<1,3> Hother) const {
291  Point2 d = pose.t() - t_;
292  if (!Hpose && !Hother) return d.norm();
293  Matrix12 D_r_d;
294  double r = norm2(d, D_r_d);
295  if (Hpose) {
296  Matrix23 D_d_pose;
297  D_d_pose <<
298  -r_.c(), r_.s(), 0.0,
299  -r_.s(), -r_.c(), 0.0;
300  *Hpose = D_r_d * D_d_pose;
301  }
302  if (Hother) {
303  Matrix23 D_d_other;
304  D_d_other <<
305  pose.r_.c(), -pose.r_.s(), 0.0,
306  pose.r_.s(), pose.r_.c(), 0.0;
307  *Hother = D_r_d * D_d_other;
308  }
309  return r;
310 }
311 
312 /* *************************************************************************
313  * Align finds the angle using a linear method:
314  * a = Pose2::transformFrom(b) = t + R*b
315  * We need to remove the centroids from the data to find the rotation
316  * using db=[dbx;dby] and a=[dax;day] we have
317  * |dax| |c -s| |dbx| |dbx -dby| |c|
318  * | | = | | * | | = | | * | | = H_i*cs
319  * |day| |s c| |dby| |dby dbx| |s|
320  * where the Hi are the 2*2 matrices. Then we will minimize the criterion
321  * J = \sum_i norm(a_i - H_i * cs)
322  * Taking the derivative with respect to cs and setting to zero we have
323  * cs = (\sum_i H_i' * a_i)/(\sum H_i'*H_i)
324  * The hessian is diagonal and just divides by a constant, but this
325  * normalization constant is irrelevant, since we take atan2.
326  * i.e., cos ~ sum(dbx*dax + dby*day) and sin ~ sum(-dby*dax + dbx*day)
327  * The translation is then found from the centroids
328  * as they also satisfy ca = t + R*cb, hence t = ca - R*cb
329  */
330 
331 std::optional<Pose2> Pose2::Align(const Point2Pairs &ab_pairs) {
332  const size_t n = ab_pairs.size();
333  if (n < 2) {
334  return {}; // we need at least 2 pairs
335  }
336 
337  // calculate centroids
338  Point2 ca(0, 0), cb(0, 0);
339  for (const Point2Pair& pair : ab_pairs) {
340  ca += pair.first;
341  cb += pair.second;
342  }
343  const double f = 1.0/n;
344  ca *= f;
345  cb *= f;
346 
347  // calculate cos and sin
348  double c = 0, s = 0;
349  for (const Point2Pair& pair : ab_pairs) {
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();
354  }
355 
356  // calculate angle and translation
357  const double theta = atan2(s, c);
358  const Rot2 R = Rot2::fromAngle(theta);
359  const Point2 t = ca - R*cb;
360  return Pose2(R, t);
361 }
362 
363 std::optional<Pose2> Pose2::Align(const Matrix& a, const Matrix& b) {
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.");
367  }
368  Point2Pairs ab_pairs;
369  for (Eigen::Index j = 0; j < a.cols(); j++) {
370  ab_pairs.emplace_back(a.col(j), b.col(j));
371  }
372  return Pose2::Align(ab_pairs);
373 }
374 
375 /* ************************************************************************* */
376 } // namespace gtsam
gtsam::internal::rotation
Rot3 rotation(const Pose3 &pose, OptionalJacobian< 3, 6 > H)
Definition: slam/expressions.h:80
w
RowVector3d w
Definition: Matrix_resize_int.cpp:3
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
Definition: gnuplot_common_settings.hh:74
Eigen::internal::print
EIGEN_STRONG_INLINE Packet4f print(const Packet4f &a)
Definition: NEON/PacketMath.h:3115
Pose2.h
2D Pose
pose
static const Pose3 pose(Rot3(Vector3(1, -1, -1).asDiagonal()), Point3(0, 0, 0.5))
inverse
const EIGEN_DEVICE_FUNC InverseReturnType inverse() const
Definition: ArrayCwiseUnaryOps.h:411
concepts.h
Concept-checking macros for geometric objects Each macro instantiates a concept check structure,...
alpha
RealScalar alpha
Definition: level1_cplx_impl.h:147
s
RealScalar s
Definition: level1_cplx_impl.h:126
e
Array< double, 1, 3 > e(1./3., 0.5, 2.)
d
static const double d[K][N]
Definition: igam.h:11
screwPose2::xi
Vector xi
Definition: testPose2.cpp:148
Testable.h
Concept check for values that can be used in unit tests.
ceres::sin
Jet< T, N > sin(const Jet< T, N > &f)
Definition: jet.h:439
c
Scalar Scalar * c
Definition: benchVecAdd.cpp:17
b
Scalar * b
Definition: benchVecAdd.cpp:17
gtsam::Pose2::rotation
const Rot2 & rotation(OptionalJacobian< 1, 3 > Hself={}) const
rotation
Definition: Pose2.h:274
x
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
Definition: gnuplot_common_settings.hh:12
gtsam::equal_with_abs_tol
bool equal_with_abs_tol(const Eigen::DenseBase< MATRIX > &A, const Eigen::DenseBase< MATRIX > &B, double tol=1e-9)
Definition: base/Matrix.h:80
T
Eigen::Triplet< double > T
Definition: Tutorial_sparse_example.cpp:6
gtsam::Matrix
Eigen::MatrixXd Matrix
Definition: base/Matrix.h:39
concepts.h
gtsam::Rot2::matrix
Matrix2 matrix() const
Definition: Rot2.cpp:85
gtsam::Vector3
Eigen::Vector3d Vector3
Definition: Vector.h:44
os
ofstream os("timeSchurFactors.csv")
result
Values result
Definition: OdometryOptimize.cpp:8
ceres::cos
Jet< T, N > cos(const Jet< T, N > &f)
Definition: jet.h:426
gtsam::Point2Pair
std::pair< Point2, Point2 > Point2Pair
Definition: Point2.h:35
gtsam::range
Double_ range(const Point2_ &p, const Point2_ &q)
Definition: slam/expressions.h:30
n
int n
Definition: BiCGSTAB_simple.cpp:1
gtsam_unstable.tests.test_ProjectionFactorRollingShutter.point
point
Definition: test_ProjectionFactorRollingShutter.py:25
Expmap
Pose2_ Expmap(const Vector3_ &xi)
Definition: InverseKinematicsExampleExpressions.cpp:47
simple::R0
static Rot3 R0
Definition: testInitializePose3.cpp:48
gtsam::transformFrom
Point3_ transformFrom(const Pose3_ &x, const Point3_ &p)
Definition: slam/expressions.h:47
J
JacobiRotation< float > J
Definition: Jacobi_makeJacobi.cpp:3
j
std::ptrdiff_t j
Definition: tut_arithmetic_redux_minmax.cpp:2
gtsam::transformTo
Line3 transformTo(const Pose3 &wTc, const Line3 &wL, OptionalJacobian< 4, 6 > Dpose, OptionalJacobian< 4, 4 > Dline)
Definition: Line3.cpp:94
Eigen::numext::q
EIGEN_DEVICE_FUNC const Scalar & q
Definition: SpecialFunctionsImpl.h:1984
gtsam::Point2
Vector2 Point2
Definition: Point2.h:32
Eigen::Triplet< double >
y
Scalar * y
Definition: level1_cplx_impl.h:124
matrix
Map< Matrix< T, Dynamic, Dynamic, ColMajor >, 0, OuterStride<> > matrix(T *data, int rows, int cols, int stride)
Definition: gtsam/3rdparty/Eigen/blas/common.h:110
gtsam::Pose2::theta
double theta() const
get theta
Definition: Pose2.h:256
atan2
AnnoyingScalar atan2(const AnnoyingScalar &y, const AnnoyingScalar &x)
Definition: AnnoyingScalar.h:110
tree::f
Point2(* f)(const Point3 &, OptionalJacobian< 2, 3 >)
Definition: testExpression.cpp:218
gtsam::Rot2
Definition: Rot2.h:35
a
ArrayXXi a
Definition: Array_initializer_list_23_cxx11.cpp:1
gtsam::OptionalJacobian::cols
OptionalJacobian< Rows, N > cols(int startCol)
Definition: OptionalJacobian.h:172
GTSAM_CONCEPT_POSE_INST
#define GTSAM_CONCEPT_POSE_INST(T)
Definition: geometry/concepts.h:73
gtsam::operator<<
std::ostream & operator<<(std::ostream &os, const Pose2 &pose)
Definition: Pose2.cpp:56
gtsam
traits
Definition: SFMdata.h:40
gtsam::OptionalJacobian
Definition: OptionalJacobian.h:38
gtsam::Pose2::x
double x() const
get x
Definition: Pose2.h:250
std
Definition: BFloat16.h:88
p
float * p
Definition: Tutorial_Map_using.cpp:9
v2
Vector v2
Definition: testSerializationBase.cpp:39
v
Array< int, Dynamic, 1 > v
Definition: Array_initializer_list_vector_cxx11.cpp:1
gtsam::Rot3::transpose
Matrix3 transpose() const
Definition: Rot3M.cpp:143
gtsam::R_PI_2
static const Rot2 R_PI_2(Rot2::fromCosSin(0., 1.))
gtsam::Rot3::matrix
Matrix3 matrix() const
Definition: Rot3M.cpp:218
gtsam::tol
const G double tol
Definition: Group.h:79
gtsam::Point2Pairs
std::vector< Point2Pair > Point2Pairs
Definition: Point2.h:38
setZero
v setZero(3)
abs
#define abs(x)
Definition: datatypes.h:17
gtsam::internal::Align
static Similarity2 Align(const Point2Pairs &d_abPointPairs, const Rot2 &aRb, const Point2Pair &centroids)
This method estimates the similarity transform from differences point pairs, given a known or estimat...
Definition: Similarity2.cpp:74
align_3::t
Point2 t(10, 10)
gtsam::norm2
double norm2(const Point2 &p, OptionalJacobian< 1, 2 > H)
Distance of the point from the origin, with Jacobian.
Definition: Point2.cpp:27
gtsam::Pose2::y
double y() const
get y
Definition: Pose2.h:253
R
Rot2 R(Rot2::fromAngle(0.1))
v1
Vector v1
Definition: testSerializationBase.cpp:38
gtsam::Pose2
Definition: Pose2.h:39
Eigen::Index
EIGEN_DEFAULT_DENSE_INDEX_TYPE Index
The Index type as used for the API.
Definition: Meta.h:74


gtsam
Author(s):
autogenerated on Sun Dec 22 2024 04:12:45