2009-08-29 09:24:26 +08:00
|
|
|
/**
|
|
|
|
* @file Pose2.cpp
|
|
|
|
* @brief 2D Pose
|
|
|
|
*/
|
|
|
|
|
2010-08-20 01:23:19 +08:00
|
|
|
#include <gtsam/geometry/Pose2.h>
|
|
|
|
#include <gtsam/base/Lie-inl.h>
|
2009-08-29 09:24:26 +08:00
|
|
|
|
|
|
|
using namespace std;
|
|
|
|
|
|
|
|
namespace gtsam {
|
|
|
|
|
2010-01-10 07:15:06 +08:00
|
|
|
/** Explicit instantiation of base class to export members */
|
2010-01-16 09:16:59 +08:00
|
|
|
INSTANTIATE_LIE(Pose2);
|
2010-01-10 07:15:06 +08:00
|
|
|
|
2010-02-28 17:10:39 +08:00
|
|
|
static const Matrix I3 = eye(3), Z12 = zeros(1,2);
|
Rot2 "named constructors" (http://www.parashift.com/c++-faq-lite/ctors.html#faq-10.8):
/** Named constructor from angle == exponential map at identity */
static Rot2 fromAngle(double theta) { return Rot2(cos(theta),sin(theta));}
/** Named constructor from cos(theta),sin(theta) pair, will *not* normalize! */
static Rot2 fromCosSin(double c, double s);
/** Named constructor that behaves as atan2, i.e., y,x order (!) and normalizes */
static Rot2 atan2(double y, double x);
which are a bit more verbose, but at least won't cause hours of bug-tracking :-(
I also made most compose, inverse, and rotate functions into methods, with the global functions mostly calling the methods. Methods have privileged access to members and hence are typically much more readable.
2010-03-03 11:31:53 +08:00
|
|
|
static const Rot2 R_PI_2(Rot2::fromCosSin(0., 1.));
|
2010-02-24 14:14:02 +08:00
|
|
|
|
2010-02-19 00:27:01 +08:00
|
|
|
/* ************************************************************************* */
|
|
|
|
Matrix Pose2::matrix() const {
|
|
|
|
Matrix R = r_.matrix();
|
2010-02-28 17:10:39 +08:00
|
|
|
R = stack(2, &R, &Z12);
|
2010-02-19 00:27:01 +08:00
|
|
|
Matrix T = Matrix_(3,1, t_.x(), t_.y(), 1.0);
|
|
|
|
return collect(2, &R, &T);
|
|
|
|
}
|
|
|
|
|
2009-12-15 08:00:02 +08:00
|
|
|
/* ************************************************************************* */
|
|
|
|
void Pose2::print(const string& s) const {
|
|
|
|
cout << s << "(" << t_.x() << ", " << t_.y() << ", " << r_.theta() << ")" << endl;
|
|
|
|
}
|
2009-08-29 09:24:26 +08:00
|
|
|
|
2009-12-15 08:00:02 +08:00
|
|
|
/* ************************************************************************* */
|
|
|
|
bool Pose2::equals(const Pose2& q, double tol) const {
|
|
|
|
return t_.equals(q.t_, tol) && r_.equals(q.r_, tol);
|
|
|
|
}
|
2009-08-29 09:24:26 +08:00
|
|
|
|
2010-02-28 17:10:39 +08:00
|
|
|
/* ************************************************************************* */
|
Rot2 "named constructors" (http://www.parashift.com/c++-faq-lite/ctors.html#faq-10.8):
/** Named constructor from angle == exponential map at identity */
static Rot2 fromAngle(double theta) { return Rot2(cos(theta),sin(theta));}
/** Named constructor from cos(theta),sin(theta) pair, will *not* normalize! */
static Rot2 fromCosSin(double c, double s);
/** Named constructor that behaves as atan2, i.e., y,x order (!) and normalizes */
static Rot2 atan2(double y, double x);
which are a bit more verbose, but at least won't cause hours of bug-tracking :-(
I also made most compose, inverse, and rotate functions into methods, with the global functions mostly calling the methods. Methods have privileged access to members and hence are typically much more readable.
2010-03-03 11:31:53 +08:00
|
|
|
|
|
|
|
#ifdef SLOW_BUT_CORRECT_EXPMAP
|
|
|
|
|
|
|
|
template<> Pose2 expmap(const Vector& xi) {
|
|
|
|
Point2 v(xi(0),xi(1));
|
|
|
|
double w = xi(2);
|
|
|
|
if (fabs(w) < 1e-5)
|
|
|
|
return Pose2(xi[0], xi[1], xi[2]);
|
|
|
|
else {
|
|
|
|
Rot2 R(Rot2::fromAngle(w));
|
|
|
|
Point2 v_ortho = R_PI_2 * v; // points towards rot center
|
2010-08-27 03:55:40 +08:00
|
|
|
Point2 t = (v_ortho - R.rotate(v_ortho)) / w;
|
Rot2 "named constructors" (http://www.parashift.com/c++-faq-lite/ctors.html#faq-10.8):
/** Named constructor from angle == exponential map at identity */
static Rot2 fromAngle(double theta) { return Rot2(cos(theta),sin(theta));}
/** Named constructor from cos(theta),sin(theta) pair, will *not* normalize! */
static Rot2 fromCosSin(double c, double s);
/** Named constructor that behaves as atan2, i.e., y,x order (!) and normalizes */
static Rot2 atan2(double y, double x);
which are a bit more verbose, but at least won't cause hours of bug-tracking :-(
I also made most compose, inverse, and rotate functions into methods, with the global functions mostly calling the methods. Methods have privileged access to members and hence are typically much more readable.
2010-03-03 11:31:53 +08:00
|
|
|
return Pose2(R, t);
|
|
|
|
}
|
|
|
|
}
|
|
|
|
|
|
|
|
Vector logmap(const Pose2& p) {
|
|
|
|
const Rot2& R = p.r();
|
|
|
|
const Point2& t = p.t();
|
|
|
|
double w = R.theta();
|
|
|
|
if (fabs(w) < 1e-5)
|
|
|
|
return Vector_(3, t.x(), t.y(), w);
|
|
|
|
else {
|
|
|
|
double c_1 = R.c()-1.0, s = R.s();
|
|
|
|
double det = c_1*c_1 + s*s;
|
2010-08-27 03:55:40 +08:00
|
|
|
Point2 p = R_PI_2 * (R.unrotate(t) - t);
|
Rot2 "named constructors" (http://www.parashift.com/c++-faq-lite/ctors.html#faq-10.8):
/** Named constructor from angle == exponential map at identity */
static Rot2 fromAngle(double theta) { return Rot2(cos(theta),sin(theta));}
/** Named constructor from cos(theta),sin(theta) pair, will *not* normalize! */
static Rot2 fromCosSin(double c, double s);
/** Named constructor that behaves as atan2, i.e., y,x order (!) and normalizes */
static Rot2 atan2(double y, double x);
which are a bit more verbose, but at least won't cause hours of bug-tracking :-(
I also made most compose, inverse, and rotate functions into methods, with the global functions mostly calling the methods. Methods have privileged access to members and hence are typically much more readable.
2010-03-03 11:31:53 +08:00
|
|
|
Point2 v = (w/det) * p;
|
|
|
|
return Vector_(3, v.x(), v.y(), w);
|
|
|
|
}
|
|
|
|
}
|
|
|
|
|
|
|
|
#else
|
|
|
|
|
2010-08-20 04:03:06 +08:00
|
|
|
/* ************************************************************************* */
|
|
|
|
Pose2 Pose2::Expmap(const Vector& v) {
|
|
|
|
return Pose2(v[0], v[1], v[2]);
|
|
|
|
}
|
Rot2 "named constructors" (http://www.parashift.com/c++-faq-lite/ctors.html#faq-10.8):
/** Named constructor from angle == exponential map at identity */
static Rot2 fromAngle(double theta) { return Rot2(cos(theta),sin(theta));}
/** Named constructor from cos(theta),sin(theta) pair, will *not* normalize! */
static Rot2 fromCosSin(double c, double s);
/** Named constructor that behaves as atan2, i.e., y,x order (!) and normalizes */
static Rot2 atan2(double y, double x);
which are a bit more verbose, but at least won't cause hours of bug-tracking :-(
I also made most compose, inverse, and rotate functions into methods, with the global functions mostly calling the methods. Methods have privileged access to members and hence are typically much more readable.
2010-03-03 11:31:53 +08:00
|
|
|
|
2010-08-20 04:03:06 +08:00
|
|
|
/* ************************************************************************* */
|
|
|
|
Vector Pose2::Logmap(const Pose2& p) {
|
|
|
|
return Vector_(3, p.x(), p.y(), p.theta());
|
|
|
|
}
|
Rot2 "named constructors" (http://www.parashift.com/c++-faq-lite/ctors.html#faq-10.8):
/** Named constructor from angle == exponential map at identity */
static Rot2 fromAngle(double theta) { return Rot2(cos(theta),sin(theta));}
/** Named constructor from cos(theta),sin(theta) pair, will *not* normalize! */
static Rot2 fromCosSin(double c, double s);
/** Named constructor that behaves as atan2, i.e., y,x order (!) and normalizes */
static Rot2 atan2(double y, double x);
which are a bit more verbose, but at least won't cause hours of bug-tracking :-(
I also made most compose, inverse, and rotate functions into methods, with the global functions mostly calling the methods. Methods have privileged access to members and hence are typically much more readable.
2010-03-03 11:31:53 +08:00
|
|
|
|
|
|
|
#endif
|
|
|
|
|
|
|
|
/* ************************************************************************* */
|
2010-02-28 17:10:39 +08:00
|
|
|
// Calculate Adjoint map
|
|
|
|
// Ad_pose is 3*3 matrix that when applied to twist xi, returns Ad_pose(xi)
|
2010-08-23 05:45:53 +08:00
|
|
|
Matrix Pose2::AdjointMap() const {
|
|
|
|
double c = r_.c(), s = r_.s(), x = t_.x(), y = t_.y();
|
|
|
|
return Matrix_(3,3,
|
|
|
|
c, -s, y,
|
|
|
|
s, c, -x,
|
|
|
|
0.0, 0.0, 1.0
|
|
|
|
);
|
|
|
|
}
|
2010-02-28 17:10:39 +08:00
|
|
|
|
|
|
|
/* ************************************************************************* */
|
2010-08-27 03:55:40 +08:00
|
|
|
Pose2 Pose2::inverse(boost::optional<Matrix&> H1) const {
|
|
|
|
if (H1) *H1 = -AdjointMap();
|
2010-08-23 05:45:53 +08:00
|
|
|
return Pose2(r_.inverse(), r_.unrotate(Point2(-t_.x(), -t_.y())));
|
2010-08-20 04:03:06 +08:00
|
|
|
}
|
2010-02-28 17:10:39 +08:00
|
|
|
|
2009-12-15 08:00:02 +08:00
|
|
|
/* ************************************************************************* */
|
2010-03-02 10:27:09 +08:00
|
|
|
// see doc/math.lyx, SE(2) section
|
2010-08-23 05:45:53 +08:00
|
|
|
Point2 Pose2::transform_to(const Point2& point,
|
|
|
|
boost::optional<Matrix&> H1, boost::optional<Matrix&> H2) const {
|
|
|
|
Point2 d = point - t_;
|
|
|
|
Point2 q = r_.unrotate(d);
|
2010-01-12 10:08:41 +08:00
|
|
|
if (!H1 && !H2) return q;
|
|
|
|
if (H1) *H1 = Matrix_(2, 3,
|
|
|
|
-1.0, 0.0, q.y(),
|
|
|
|
0.0, -1.0, -q.x());
|
2010-08-23 05:45:53 +08:00
|
|
|
if (H2) *H2 = r_.transpose();
|
2010-01-12 10:08:41 +08:00
|
|
|
return q;
|
|
|
|
}
|
|
|
|
|
2010-03-02 10:27:09 +08:00
|
|
|
/* ************************************************************************* */
|
|
|
|
// see doc/math.lyx, SE(2) section
|
2010-08-27 03:55:40 +08:00
|
|
|
Pose2 Pose2::compose(const Pose2& p2, boost::optional<Matrix&> H1,
|
|
|
|
boost::optional<Matrix&> H2) const {
|
2010-05-24 13:40:59 +08:00
|
|
|
// TODO: inline and reuse?
|
2010-08-27 03:55:40 +08:00
|
|
|
if(H1) *H1 = p2.inverse().AdjointMap();
|
2010-05-24 13:40:59 +08:00
|
|
|
if(H2) *H2 = I3;
|
2010-08-27 03:55:40 +08:00
|
|
|
return (*this)*p2;
|
2010-05-24 13:40:59 +08:00
|
|
|
}
|
|
|
|
|
2010-02-28 16:51:43 +08:00
|
|
|
/* ************************************************************************* */
|
2010-03-01 09:33:45 +08:00
|
|
|
// see doc/math.lyx, SE(2) section
|
2010-08-23 05:45:53 +08:00
|
|
|
Point2 Pose2::transform_from(const Point2& p,
|
|
|
|
boost::optional<Matrix&> H1, boost::optional<Matrix&> H2) const {
|
|
|
|
const Point2 q = r_ * p;
|
|
|
|
if (H1 || H2) {
|
|
|
|
const Matrix R = r_.matrix();
|
|
|
|
const Matrix Drotate1 = Matrix_(2, 1, -q.y(), q.x());
|
|
|
|
if (H1) *H1 = collect(2, &R, &Drotate1); // [R R_{pi/2}q]
|
|
|
|
if (H2) *H2 = R; // R
|
|
|
|
}
|
|
|
|
return q + t_;
|
2010-02-28 16:51:43 +08:00
|
|
|
}
|
|
|
|
|
2009-12-15 08:00:02 +08:00
|
|
|
/* ************************************************************************* */
|
2010-08-27 03:55:40 +08:00
|
|
|
Pose2 Pose2::between(const Pose2& p2, boost::optional<Matrix&> H1,
|
|
|
|
boost::optional<Matrix&> H2) const {
|
2010-08-23 05:45:53 +08:00
|
|
|
// get cosines and sines from rotation matrices
|
2010-08-27 03:55:40 +08:00
|
|
|
const Rot2& R1 = r_, R2 = p2.r();
|
2010-08-23 05:45:53 +08:00
|
|
|
double c1=R1.c(), s1=R1.s(), c2=R2.c(), s2=R2.s();
|
|
|
|
|
|
|
|
// Calculate delta rotation = between(R1,R2)
|
|
|
|
double c = c1 * c2 + s1 * s2, s = -s1 * c2 + c1 * s2;
|
|
|
|
Rot2 R(Rot2::atan2(s,c)); // normalizes
|
|
|
|
|
|
|
|
// Calculate delta translation = unrotate(R1, dt);
|
2010-08-27 03:55:40 +08:00
|
|
|
Point2 dt = p2.t() - t_;
|
2010-08-23 05:45:53 +08:00
|
|
|
double x = dt.x(), y = dt.y();
|
|
|
|
Point2 t(c1 * x + s1 * y, -s1 * x + c1 * y);
|
|
|
|
|
|
|
|
// FD: This is just -AdjointMap(between(p2,p1)) inlined and re-using above
|
|
|
|
if (H1) {
|
|
|
|
double dt1 = -s2 * x + c2 * y;
|
|
|
|
double dt2 = -c2 * x - s2 * y;
|
|
|
|
H1->resize(3,3);
|
|
|
|
double data[9] = {
|
|
|
|
-c, -s, dt1,
|
|
|
|
s, -c, dt2,
|
|
|
|
0.0, 0.0, -1.0};
|
|
|
|
copy(data, data+9, H1->data().begin());
|
|
|
|
}
|
|
|
|
if (H2) *H2 = I3;
|
|
|
|
|
|
|
|
return Pose2(R,t);
|
|
|
|
}
|
2009-12-09 03:12:20 +08:00
|
|
|
|
2010-01-16 09:16:59 +08:00
|
|
|
/* ************************************************************************* */
|
2010-08-23 05:45:53 +08:00
|
|
|
Rot2 Pose2::bearing(const Point2& point,
|
|
|
|
boost::optional<Matrix&> H1, boost::optional<Matrix&> H2) const {
|
|
|
|
Point2 d = transform_to(point, H1, H2);
|
|
|
|
if (!H1 && !H2) return Rot2::relativeBearing(d);
|
|
|
|
Matrix D_result_d;
|
|
|
|
Rot2 result = Rot2::relativeBearing(d, D_result_d);
|
|
|
|
if (H1) *H1 = D_result_d * (*H1);
|
|
|
|
if (H2) *H2 = D_result_d * (*H2);
|
|
|
|
return result;
|
|
|
|
}
|
2010-01-16 09:16:59 +08:00
|
|
|
|
|
|
|
/* ************************************************************************* */
|
2010-08-23 05:45:53 +08:00
|
|
|
double Pose2::range(const Point2& point,
|
|
|
|
boost::optional<Matrix&> H1, boost::optional<Matrix&> H2) const {
|
|
|
|
if (!H1 && !H2) return transform_to(point).norm();
|
|
|
|
Point2 d = transform_to(point, H1, H2);
|
|
|
|
double x = d.x(), y = d.y(), d2 = x * x + y * y, n = sqrt(d2);
|
|
|
|
Matrix D_result_d = Matrix_(1, 2, x / n, y / n);
|
|
|
|
if (H1) *H1 = D_result_d * (*H1);
|
|
|
|
if (H2) *H2 = D_result_d * (*H2);
|
|
|
|
return n;
|
|
|
|
}
|
2009-12-09 03:12:20 +08:00
|
|
|
|
2009-12-15 08:00:02 +08:00
|
|
|
/* ************************************************************************* */
|
2009-08-29 09:24:26 +08:00
|
|
|
} // namespace gtsam
|