2009-12-10 05:50:27 +08:00
|
|
|
/*
|
|
|
|
* Rot2.cpp
|
|
|
|
*
|
|
|
|
* Created on: Dec 9, 2009
|
|
|
|
* Author: Frank Dellaert
|
|
|
|
*/
|
|
|
|
|
|
|
|
#include "Rot2.h"
|
2010-01-10 07:15:06 +08:00
|
|
|
#include "Lie-inl.h"
|
2009-12-10 05:50:27 +08:00
|
|
|
|
|
|
|
using namespace std;
|
|
|
|
|
|
|
|
namespace gtsam {
|
|
|
|
|
2010-01-16 09:16:59 +08:00
|
|
|
/** Explicit instantiation of base class to export members */
|
|
|
|
INSTANTIATE_LIE(Rot2);
|
2010-01-15 00:57:48 +08:00
|
|
|
|
2010-03-03 13:35:00 +08:00
|
|
|
/* ************************************************************************* */
|
|
|
|
Rot2 Rot2::fromCosSin(double c, double s) {
|
|
|
|
if (fabs(c * c + s * s - 1.0) > 1e-9) throw std::invalid_argument(
|
|
|
|
"Rot2::fromCosSin: needs cos/sin pair");
|
|
|
|
return Rot2(c, s);
|
|
|
|
}
|
|
|
|
|
|
|
|
/* ************************************************************************* */
|
|
|
|
Rot2 Rot2::atan2(double y, double x) {
|
|
|
|
Rot2 R(x, y);
|
|
|
|
return R.normalize();
|
|
|
|
}
|
|
|
|
|
2010-01-15 00:57:48 +08:00
|
|
|
/* ************************************************************************* */
|
|
|
|
void Rot2::print(const string& s) const {
|
|
|
|
cout << s << ":" << theta() << endl;
|
|
|
|
}
|
|
|
|
|
|
|
|
/* ************************************************************************* */
|
|
|
|
bool Rot2::equals(const Rot2& R, double tol) const {
|
|
|
|
return fabs(c_ - R.c_) <= tol && fabs(s_ - R.s_) <= tol;
|
|
|
|
}
|
|
|
|
|
2010-03-03 13:35:00 +08:00
|
|
|
/* ************************************************************************* */
|
|
|
|
Rot2& Rot2::normalize() {
|
|
|
|
double scale = c_*c_ + s_*s_;
|
|
|
|
if(fabs(scale-1.0)>1e-9) {
|
|
|
|
scale = pow(scale, -0.5);
|
|
|
|
c_ *= scale;
|
|
|
|
s_ *= scale;
|
|
|
|
}
|
|
|
|
return *this;
|
|
|
|
}
|
|
|
|
|
2010-01-15 00:57:48 +08:00
|
|
|
/* ************************************************************************* */
|
|
|
|
Matrix Rot2::matrix() const {
|
|
|
|
return Matrix_(2, 2, c_, -s_, s_, c_);
|
|
|
|
}
|
|
|
|
|
|
|
|
/* ************************************************************************* */
|
|
|
|
Matrix Rot2::transpose() const {
|
|
|
|
return Matrix_(2, 2, c_, s_, -s_, c_);
|
|
|
|
}
|
|
|
|
|
|
|
|
/* ************************************************************************* */
|
|
|
|
Point2 Rot2::rotate(const Point2& p) const {
|
|
|
|
return Point2(c_ * p.x() + -s_ * p.y(), s_ * p.x() + c_ * p.y());
|
|
|
|
}
|
|
|
|
|
|
|
|
/* ************************************************************************* */
|
|
|
|
Point2 Rot2::unrotate(const Point2& p) const {
|
|
|
|
return Point2(c_ * p.x() + s_ * p.y(), -s_ * p.x() + c_ * p.y());
|
|
|
|
}
|
|
|
|
|
|
|
|
/* ************************************************************************* */
|
2010-03-01 09:37:50 +08:00
|
|
|
// see doc/math.lyx, SO(2) section
|
|
|
|
Point2 rotate(const Rot2 & R, const Point2& p, boost::optional<Matrix&> H1,
|
|
|
|
boost::optional<Matrix&> H2) {
|
2010-01-15 00:57:48 +08:00
|
|
|
Point2 q = R * p;
|
|
|
|
if (H1) *H1 = Matrix_(2, 1, -q.y(), q.x());
|
|
|
|
if (H2) *H2 = R.matrix();
|
|
|
|
return q;
|
|
|
|
}
|
|
|
|
|
|
|
|
/* ************************************************************************* */
|
2010-03-01 09:37:50 +08:00
|
|
|
// see doc/math.lyx, SO(2) section
|
2010-01-15 00:57:48 +08:00
|
|
|
Point2 unrotate(const Rot2 & R, const Point2& p,
|
|
|
|
boost::optional<Matrix&> H1, boost::optional<Matrix&> H2) {
|
|
|
|
Point2 q = R.unrotate(p);
|
2010-03-01 09:37:50 +08:00
|
|
|
if (H1) *H1 = Matrix_(2, 1, q.y(), -q.x()); // R_{pi/2}q
|
2010-01-15 00:57:48 +08:00
|
|
|
if (H2) *H2 = R.transpose();
|
|
|
|
return q;
|
|
|
|
}
|
|
|
|
|
|
|
|
/* ************************************************************************* */
|
|
|
|
Rot2 relativeBearing(const Point2& d) {
|
|
|
|
double n = d.norm();
|
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 Rot2::fromCosSin(d.x() / n, d.y() / n);
|
2010-01-15 00:57:48 +08:00
|
|
|
}
|
|
|
|
|
|
|
|
/* ************************************************************************* */
|
|
|
|
Rot2 relativeBearing(const Point2& d, boost::optional<Matrix&> H) {
|
|
|
|
double x = d.x(), y = d.y(), d2 = x * x + y * y, n = sqrt(d2);
|
|
|
|
if (H) *H = Matrix_(1, 2, -y / d2, x / d2);
|
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 Rot2::fromCosSin(x / n, y / n);
|
2010-01-15 00:57:48 +08:00
|
|
|
}
|
|
|
|
|
|
|
|
/* ************************************************************************* */
|
2009-12-10 05:50:27 +08:00
|
|
|
|
|
|
|
} // gtsam
|