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 <iostream>
24 #include <iomanip>
25 
26 using namespace std;
27 
28 namespace gtsam {
29 
32 
33 static const Rot2 R_PI_2(Rot2::fromCosSin(0., 1.));
34 
35 /* ************************************************************************* */
36 Matrix3 Pose2::matrix() const {
37  Matrix2 R = r_.matrix();
38  Matrix32 R0;
39  R0.block<2,2>(0,0) = R;
40  R0.block<1,2>(2,0).setZero();
41  Matrix31 T;
42  T << t_.x(), t_.y(), 1.0;
43  Matrix3 RT_;
44  RT_.block<3,2>(0,0) = R0;
45  RT_.block<3,1>(0,2) = T;
46  return RT_;
47 }
48 
49 /* ************************************************************************* */
50 void Pose2::print(const string& s) const {
51  std::cout << (s.empty() ? s : s + " ") << *this << std::endl;
52 }
53 
54 /* ************************************************************************* */
55 std::ostream &operator<<(std::ostream &os, const Pose2& pose) {
56  os << "(" << pose.x() << ", " << pose.y() << ", " << pose.theta() << ")";
57  return os;
58 }
59 
60 /* ************************************************************************* */
61 bool Pose2::equals(const Pose2& q, double tol) const {
62  return equal_with_abs_tol(t_, q.t_, tol) && r_.equals(q.r_, tol);
63 }
64 
65 /* ************************************************************************* */
67  assert(xi.size() == 3);
68  if (H) *H = Pose2::ExpmapDerivative(xi);
69  const Point2 v(xi(0),xi(1));
70  const double w = xi(2);
71  if (std::abs(w) < 1e-10)
72  return Pose2(xi[0], xi[1], xi[2]);
73  else {
74  const Rot2 R(Rot2::fromAngle(w));
75  const Point2 v_ortho = R_PI_2 * v; // points towards rot center
76  const Point2 t = (v_ortho - R.rotate(v_ortho)) / w;
77  return Pose2(R, t);
78  }
79 }
80 
81 /* ************************************************************************* */
82 Vector3 Pose2::Logmap(const Pose2& p, OptionalJacobian<3, 3> H) {
83  if (H) *H = Pose2::LogmapDerivative(p);
84  const Rot2& R = p.r();
85  const Point2& t = p.t();
86  double w = R.theta();
87  if (std::abs(w) < 1e-10)
88  return Vector3(t.x(), t.y(), w);
89  else {
90  double c_1 = R.c()-1.0, s = R.s();
91  double det = c_1*c_1 + s*s;
92  Point2 p = R_PI_2 * (R.unrotate(t) - t);
93  Point2 v = (w/det) * p;
94  return Vector3(v.x(), v.y(), w);
95  }
96 }
97 
98 /* ************************************************************************* */
99 Pose2 Pose2::ChartAtOrigin::Retract(const Vector3& v, ChartJacobian H) {
100 #ifdef SLOW_BUT_CORRECT_EXPMAP
101  return Expmap(v, H);
102 #else
103  if (H) {
104  *H = I_3x3;
105  H->topLeftCorner<2,2>() = Rot2(-v[2]).matrix();
106  }
107  return Pose2(v[0], v[1], v[2]);
108 #endif
109 }
110 /* ************************************************************************* */
111 Vector3 Pose2::ChartAtOrigin::Local(const Pose2& r, ChartJacobian H) {
112 #ifdef SLOW_BUT_CORRECT_EXPMAP
113  return Logmap(r, H);
114 #else
115  if (H) {
116  *H = I_3x3;
117  H->topLeftCorner<2,2>() = r.rotation().matrix();
118  }
119  return Vector3(r.x(), r.y(), r.theta());
120 #endif
121 }
122 
123 /* ************************************************************************* */
124 // Calculate Adjoint map
125 // Ad_pose is 3*3 matrix that when applied to twist xi, returns Ad_pose(xi)
126 Matrix3 Pose2::AdjointMap() const {
127  double c = r_.c(), s = r_.s(), x = t_.x(), y = t_.y();
128  Matrix3 rvalue;
129  rvalue <<
130  c, -s, y,
131  s, c, -x,
132  0.0, 0.0, 1.0;
133  return rvalue;
134 }
135 
136 /* ************************************************************************* */
137 Matrix3 Pose2::adjointMap(const Vector3& v) {
138  // See Chirikjian12book2, vol.2, pg. 36
139  Matrix3 ad = Z_3x3;
140  ad(0,1) = -v[2];
141  ad(1,0) = v[2];
142  ad(0,2) = v[1];
143  ad(1,2) = -v[0];
144  return ad;
145 }
146 
147 /* ************************************************************************* */
148 Matrix3 Pose2::ExpmapDerivative(const Vector3& v) {
149  double alpha = v[2];
150  Matrix3 J;
151  if (std::abs(alpha) > 1e-5) {
152  // Chirikjian11book2, pg. 36
153  /* !!!Warning!!! Compare Iserles05an, formula 2.42 and Chirikjian11book2 pg.26
154  * Iserles' right-trivialization dexpR is actually the left Jacobian J_l in Chirikjian's notation
155  * In fact, Iserles 2.42 can be written as:
156  * \dot{g} g^{-1} = dexpR_{q}\dot{q}
157  * where q = A, and g = exp(A)
158  * and the LHS is in the definition of J_l in Chirikjian11book2, pg. 26.
159  * Hence, to compute ExpmapDerivative, we have to use the formula of J_r Chirikjian11book2, pg.36
160  */
161  double sZalpha = sin(alpha)/alpha, c_1Zalpha = (cos(alpha)-1)/alpha;
162  double v1Zalpha = v[0]/alpha, v2Zalpha = v[1]/alpha;
163  J << sZalpha, -c_1Zalpha, v1Zalpha + v2Zalpha*c_1Zalpha - v1Zalpha*sZalpha,
164  c_1Zalpha, sZalpha, -v1Zalpha*c_1Zalpha + v2Zalpha - v2Zalpha*sZalpha,
165  0, 0, 1;
166  }
167  else {
168  // Thanks to Krunal: Apply L'Hospital rule to several times to
169  // compute the limits when alpha -> 0
170  J << 1,0,-0.5*v[1],
171  0,1, 0.5*v[0],
172  0,0, 1;
173  }
174 
175  return J;
176 }
177 
178 /* ************************************************************************* */
179 Matrix3 Pose2::LogmapDerivative(const Pose2& p) {
180  Vector3 v = Logmap(p);
181  double alpha = v[2];
182  Matrix3 J;
183  if (std::abs(alpha) > 1e-5) {
184  double alphaInv = 1/alpha;
185  double halfCotHalfAlpha = 0.5*sin(alpha)/(1-cos(alpha));
186  double v1 = v[0], v2 = v[1];
187 
188  J << alpha*halfCotHalfAlpha, -0.5*alpha, v1*alphaInv - v1*halfCotHalfAlpha + 0.5*v2,
189  0.5*alpha, alpha*halfCotHalfAlpha, v2*alphaInv - 0.5*v1 - v2*halfCotHalfAlpha,
190  0, 0, 1;
191  }
192  else {
193  J << 1,0, 0.5*v[1],
194  0,1, -0.5*v[0],
195  0,0, 1;
196  }
197  return J;
198 }
199 
200 /* ************************************************************************* */
202  return Pose2(r_.inverse(), r_.unrotate(Point2(-t_.x(), -t_.y())));
203 }
204 
205 /* ************************************************************************* */
206 // see doc/math.lyx, SE(2) section
208  OptionalJacobian<2, 3> Hpose, OptionalJacobian<2, 2> Hpoint) const {
209  OptionalJacobian<2, 2> Htranslation = Hpose.cols<2>(0);
210  OptionalJacobian<2, 1> Hrotation = Hpose.cols<1>(2);
211  const Point2 q = r_.unrotate(point - t_, Hrotation, Hpoint);
212  if (Htranslation) *Htranslation << -1.0, 0.0, 0.0, -1.0;
213  return q;
214 }
215 
216 /* ************************************************************************* */
217 // see doc/math.lyx, SE(2) section
219  OptionalJacobian<2, 3> Hpose, OptionalJacobian<2, 2> Hpoint) const {
220  OptionalJacobian<2, 2> Htranslation = Hpose.cols<2>(0);
221  OptionalJacobian<2, 1> Hrotation = Hpose.cols<1>(2);
222  const Point2 q = r_.rotate(point, Hrotation, Hpoint);
223  if (Htranslation) *Htranslation = (Hpoint ? *Hpoint : r_.matrix());
224  return q + t_;
225 }
226 
227 /* ************************************************************************* */
228 Rot2 Pose2::bearing(const Point2& point,
229  OptionalJacobian<1, 3> Hpose, OptionalJacobian<1, 2> Hpoint) const {
230  // make temporary matrices
231  Matrix23 D_d_pose; Matrix2 D_d_point;
232  Point2 d = transformTo(point, Hpose ? &D_d_pose : 0, Hpoint ? &D_d_point : 0);
233  if (!Hpose && !Hpoint) return Rot2::relativeBearing(d);
234  Matrix12 D_result_d;
235  Rot2 result = Rot2::relativeBearing(d, Hpose || Hpoint ? &D_result_d : 0);
236  if (Hpose) *Hpose = D_result_d * D_d_pose;
237  if (Hpoint) *Hpoint = D_result_d * D_d_point;
238  return result;
239 }
240 
241 /* ************************************************************************* */
242 Rot2 Pose2::bearing(const Pose2& pose,
243  OptionalJacobian<1, 3> Hpose, OptionalJacobian<1, 3> Hother) const {
244  Matrix12 D2;
245  Rot2 result = bearing(pose.t(), Hpose, Hother ? &D2 : 0);
246  if (Hother) {
247  Matrix12 H2_ = D2 * pose.r().matrix();
248  *Hother << H2_, Z_1x1;
249  }
250  return result;
251 }
252 /* ************************************************************************* */
253 double Pose2::range(const Point2& point,
254  OptionalJacobian<1,3> Hpose, OptionalJacobian<1,2> Hpoint) const {
255  Point2 d = point - t_;
256  if (!Hpose && !Hpoint) return d.norm();
257  Matrix12 D_r_d;
258  double r = norm2(d, D_r_d);
259  if (Hpose) {
260  Matrix23 D_d_pose;
261  D_d_pose << -r_.c(), r_.s(), 0.0,
262  -r_.s(), -r_.c(), 0.0;
263  *Hpose = D_r_d * D_d_pose;
264  }
265  if (Hpoint) *Hpoint = D_r_d;
266  return r;
267 }
268 
269 /* ************************************************************************* */
270 double Pose2::range(const Pose2& pose,
271  OptionalJacobian<1,3> Hpose,
272  OptionalJacobian<1,3> Hother) const {
273  Point2 d = pose.t() - t_;
274  if (!Hpose && !Hother) 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 <<
280  -r_.c(), r_.s(), 0.0,
281  -r_.s(), -r_.c(), 0.0;
282  *Hpose = D_r_d * D_d_pose;
283  }
284  if (Hother) {
285  Matrix23 D_d_other;
286  D_d_other <<
287  pose.r_.c(), -pose.r_.s(), 0.0,
288  pose.r_.s(), pose.r_.c(), 0.0;
289  *Hother = D_r_d * D_d_other;
290  }
291  return r;
292 }
293 
294 /* *************************************************************************
295  * New explanation, from scan.ml
296  * It finds the angle using a linear method:
297  * q = Pose2::transformFrom(p) = t + R*p
298  * We need to remove the centroids from the data to find the rotation
299  * using dp=[dpx;dpy] and q=[dqx;dqy] we have
300  * |dqx| |c -s| |dpx| |dpx -dpy| |c|
301  * | | = | | * | | = | | * | | = H_i*cs
302  * |dqy| |s c| |dpy| |dpy dpx| |s|
303  * where the Hi are the 2*2 matrices. Then we will minimize the criterion
304  * J = \sum_i norm(q_i - H_i * cs)
305  * Taking the derivative with respect to cs and setting to zero we have
306  * cs = (\sum_i H_i' * q_i)/(\sum H_i'*H_i)
307  * The hessian is diagonal and just divides by a constant, but this
308  * normalization constant is irrelevant, since we take atan2.
309  * i.e., cos ~ sum(dpx*dqx + dpy*dqy) and sin ~ sum(-dpy*dqx + dpx*dqy)
310  * The translation is then found from the centroids
311  * as they also satisfy cq = t + R*cp, hence t = cq - R*cp
312  */
313 
314 boost::optional<Pose2> align(const vector<Point2Pair>& pairs) {
315 
316  size_t n = pairs.size();
317  if (n<2) return boost::none; // we need at least two pairs
318 
319  // calculate centroids
320  Point2 cp(0,0), cq(0,0);
321  for(const Point2Pair& pair: pairs) {
322  cp += pair.first;
323  cq += pair.second;
324  }
325  double f = 1.0/n;
326  cp *= f; cq *= f;
327 
328  // calculate cos and sin
329  double c=0,s=0;
330  for(const Point2Pair& pair: pairs) {
331  Point2 dp = pair.first - cp;
332  Point2 dq = pair.second - cq;
333  c += dp.x() * dq.x() + dp.y() * dq.y();
334  s += -dp.y() * dq.x() + dp.x() * dq.y();
335  }
336 
337  // calculate angle and translation
338  double theta = atan2(s,c);
339  Rot2 R = Rot2::fromAngle(theta);
340  Point2 t = cq - R*cp;
341  return Pose2(R, t);
342 }
343 
344 /* ************************************************************************* */
345 } // namespace gtsam
void print(const Matrix &A, const string &s, ostream &stream)
Definition: Matrix.cpp:155
#define GTSAM_CONCEPT_POSE_INST(T)
Point2 t_
Definition: Pose2.h:47
Scalar * y
Vector v2
Concept check for values that can be used in unit tests.
double y() const
get y
Definition: Pose2.h:218
Eigen::Vector3d Vector3
Definition: Vector.h:43
Vector v1
Point2 rotate(const Point2 &p, OptionalJacobian< 2, 1 > H1=boost::none, OptionalJacobian< 2, 2 > H2=boost::none) const
Definition: Rot2.cpp:104
std::pair< Point2, Point2 > Point2Pair
Definition: Point2.h:38
const Point2 & t() const
translation
Definition: Pose2.h:224
Vector2 Point2
Definition: Point2.h:27
ArrayXcf v
Definition: Cwise_arg.cpp:1
int n
Scalar Scalar * c
Definition: benchVecAdd.cpp:17
Rot2 R(Rot2::fromAngle(0.1))
Pose2_ Expmap(const Vector3_ &xi)
Definition: Half.h:150
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
Rot2 theta
const Rot2 & r() const
rotation
Definition: Pose2.h:227
Rot2 r_
Definition: Pose2.h:46
Point2 unrotate(const Point2 &p, OptionalJacobian< 2, 1 > H1=boost::none, OptionalJacobian< 2, 2 > H2=boost::none) const
Definition: Rot2.cpp:114
Point3 point(10, 0,-5)
EIGEN_DEVICE_FUNC const CosReturnType cos() const
Point3_ transformFrom(const Pose3_ &x, const Point3_ &p)
double theta() const
Definition: Rot2.h:183
Values result
double norm2(const Point2 &p, OptionalJacobian< 1, 2 > H)
Distance of the point from the origin, with Jacobian.
Definition: Point2.cpp:27
double theta() const
get theta
Definition: Pose2.h:221
static const Pose3 pose(Rot3(Vector3(1,-1,-1).asDiagonal()), Point3(0, 0, 0.5))
const Rot2 & rotation() const
rotation
Definition: Pose2.h:233
Eigen::Triplet< double > T
Matrix2 matrix() const
Definition: Rot2.cpp:89
Point2(* f)(const Point3 &, OptionalJacobian< 2, 3 >)
RealScalar alpha
Array< double, 1, 3 > e(1./3., 0.5, 2.)
RealScalar s
EIGEN_DEVICE_FUNC const Scalar & q
JacobiRotation< float > J
double s() const
Definition: Rot2.h:199
RowVector3d w
Jet< T, N > atan2(const Jet< T, N > &g, const Jet< T, N > &f)
Definition: jet.h:556
bool equal_with_abs_tol(const Eigen::DenseBase< MATRIX > &A, const Eigen::DenseBase< MATRIX > &B, double tol=1e-9)
Definition: base/Matrix.h:84
Vector xi
Definition: testPose2.cpp:150
traits
Definition: chartTesting.h:28
boost::optional< Pose2 > align(const vector< Point2Pair > &pairs)
Definition: Pose2.cpp:314
double x() const
get x
Definition: Pose2.h:215
ofstream os("timeSchurFactors.csv")
std::ostream & operator<<(std::ostream &os, const Pose2 &pose)
Definition: Pose2.cpp:55
static const Rot2 R_PI_2(Rot2::fromCosSin(0., 1.))
float * p
Line3 transformTo(const Pose3 &wTc, const Line3 &wL, OptionalJacobian< 4, 6 > Dpose, OptionalJacobian< 4, 4 > Dline)
Definition: Line3.cpp:94
static Rot3 R0
EIGEN_DEVICE_FUNC const SinReturnType sin() const
const G double tol
Definition: Group.h:83
double c() const
Definition: Rot2.h:194
2D Pose
Map< Matrix< T, Dynamic, Dynamic, ColMajor >, 0, OuterStride<> > matrix(T *data, int rows, int cols, int stride)
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
#define abs(x)
Definition: datatypes.h:17
EIGEN_DEVICE_FUNC const InverseReturnType inverse() const
Point2 t(10, 10)
v setZero(3)


gtsam
Author(s):
autogenerated on Sat May 8 2021 02:43:27