2009-12-10 05:50:27 +08:00
|
|
|
/*
|
|
|
|
* Rot2.h
|
|
|
|
*
|
|
|
|
* Created on: Dec 9, 2009
|
|
|
|
* Author: Frank Dellaert
|
|
|
|
*/
|
|
|
|
|
|
|
|
#ifndef ROT2_H_
|
|
|
|
#define ROT2_H_
|
|
|
|
|
2010-01-15 00:57:48 +08:00
|
|
|
#include <boost/optional.hpp>
|
2010-08-20 01:23:19 +08:00
|
|
|
#include <gtsam/base/Testable.h>
|
|
|
|
#include <gtsam/geometry/Point2.h>
|
|
|
|
#include <gtsam/base/Matrix.h>
|
|
|
|
#include <gtsam/base/Lie.h>
|
2009-12-10 05:50:27 +08:00
|
|
|
|
|
|
|
namespace gtsam {
|
|
|
|
|
2010-07-08 22:39:06 +08:00
|
|
|
/** Rotation matrix
|
|
|
|
* NOTE: the angle theta is in radians unless explicitly stated
|
|
|
|
*/
|
2010-01-10 07:15:06 +08:00
|
|
|
class Rot2: Testable<Rot2>, public Lie<Rot2> {
|
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
|
|
|
|
2009-12-15 08:00:02 +08:00
|
|
|
private:
|
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
|
|
|
|
2009-12-15 08:00:02 +08:00
|
|
|
/** we store cos(theta) and sin(theta) */
|
|
|
|
double c_, s_;
|
|
|
|
|
2010-03-03 13:35:00 +08:00
|
|
|
/** private constructor from cos/sin */
|
|
|
|
inline Rot2(double c, double s) : c_(c), s_(s) {}
|
2010-01-08 08:40:17 +08:00
|
|
|
|
2010-03-03 13:35:00 +08:00
|
|
|
/** normalize to make sure cos and sin form unit vector */
|
|
|
|
Rot2& normalize();
|
2009-12-15 08:00:02 +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
|
|
|
public:
|
|
|
|
|
2009-12-15 08:00:02 +08:00
|
|
|
/** default constructor, zero rotation */
|
|
|
|
Rot2() : c_(1.0), s_(0.0) {}
|
|
|
|
|
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
|
|
|
/** "named constructors" */
|
|
|
|
|
2010-07-08 22:39:06 +08:00
|
|
|
/** Named constructor from angle == exponential map at identity - theta is in radians*/
|
2010-03-03 13:35:00 +08:00
|
|
|
static Rot2 fromAngle(double theta);
|
2009-12-15 08:00:02 +08:00
|
|
|
|
2010-07-08 22:39:06 +08:00
|
|
|
/** Named constructor from angle in degrees */
|
|
|
|
static Rot2 fromDegrees(double theta) {
|
|
|
|
const double degree = M_PI / 180;
|
|
|
|
return fromAngle(theta * degree);
|
|
|
|
}
|
|
|
|
|
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
|
|
|
/** Named constructor from cos(theta),sin(theta) pair, will *not* normalize! */
|
2010-03-03 13:35:00 +08:00
|
|
|
static Rot2 fromCosSin(double c, double s);
|
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
|
|
|
|
|
|
|
/** Named constructor that behaves as atan2, i.e., y,x order (!) and normalizes */
|
2010-03-03 13:35:00 +08:00
|
|
|
static Rot2 atan2(double y, double x);
|
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-07-15 05:04:04 +08:00
|
|
|
/** return angle (RADIANS) */
|
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
|
|
|
double theta() const { return ::atan2(s_,c_); }
|
2009-12-15 08:00:02 +08:00
|
|
|
|
2010-07-15 05:04:04 +08:00
|
|
|
/** return angle (DEGREES) */
|
|
|
|
double degrees() const {
|
|
|
|
const double degree = M_PI / 180;
|
|
|
|
return theta() / degree;
|
|
|
|
}
|
|
|
|
|
2009-12-15 08:00:02 +08:00
|
|
|
/** return cos */
|
2010-02-24 14:14:43 +08:00
|
|
|
inline double c() const { return c_; }
|
2009-12-15 08:00:02 +08:00
|
|
|
|
|
|
|
/** return sin */
|
2010-02-24 14:14:43 +08:00
|
|
|
inline double s() const { return s_; }
|
2009-12-15 08:00:02 +08:00
|
|
|
|
|
|
|
/** print */
|
|
|
|
void print(const std::string& s = "theta") const;
|
|
|
|
|
|
|
|
/** equals with an tolerance */
|
|
|
|
bool equals(const Rot2& R, double tol = 1e-9) const;
|
|
|
|
|
|
|
|
/** return 2*2 rotation matrix */
|
|
|
|
Matrix matrix() const;
|
|
|
|
|
|
|
|
/** return 2*2 transpose (inverse) rotation matrix */
|
|
|
|
Matrix transpose() const;
|
|
|
|
|
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
|
|
|
/** The inverse rotation - negative angle */
|
|
|
|
Rot2 inverse() const { return Rot2(c_, -s_);}
|
|
|
|
|
|
|
|
/** Compose - make a new rotation by adding angles */
|
|
|
|
Rot2 operator*(const Rot2& R) const {
|
|
|
|
return fromCosSin(c_ * R.c_ - s_ * R.s_, s_ * R.c_ + c_ * R.s_);
|
|
|
|
}
|
2009-12-15 08:00:02 +08:00
|
|
|
|
2010-01-15 00:57:48 +08:00
|
|
|
/** rotate from world to rotated = R*p */
|
|
|
|
Point2 rotate(const Point2& p) const;
|
|
|
|
|
2009-12-15 08:00:02 +08:00
|
|
|
/** rotate from world to rotated = R'*p */
|
|
|
|
Point2 unrotate(const Point2& p) const;
|
|
|
|
|
2010-03-02 05:56:13 +08:00
|
|
|
/** get the dimension by the type */
|
|
|
|
static inline size_t dim() { return 1; };
|
|
|
|
|
2009-12-15 08:00:02 +08:00
|
|
|
private:
|
|
|
|
/** Serialization function */
|
|
|
|
friend class boost::serialization::access;
|
|
|
|
template<class Archive>
|
|
|
|
void serialize(Archive & ar, const unsigned int version) {
|
|
|
|
ar & BOOST_SERIALIZATION_NVP(c_);
|
|
|
|
ar & BOOST_SERIALIZATION_NVP(s_);
|
|
|
|
}
|
|
|
|
|
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
|
|
|
}; // Rot2
|
2010-01-08 08:40:17 +08:00
|
|
|
|
2010-03-03 13:35:00 +08:00
|
|
|
/* inline named constructor implementation */
|
|
|
|
inline Rot2 Rot2::fromAngle(double theta) {
|
|
|
|
return Rot2(cos(theta), sin(theta));
|
|
|
|
}
|
|
|
|
|
2010-01-08 08:40:17 +08:00
|
|
|
// Lie group functions
|
|
|
|
|
2010-01-11 06:41:23 +08:00
|
|
|
/** Global print calls member function */
|
2010-02-04 04:12:16 +08:00
|
|
|
inline void print(const Rot2& r, const std::string& s = "") { r.print(s); }
|
2010-01-11 06:41:23 +08:00
|
|
|
|
|
|
|
/** Dimensionality of the tangent space */
|
2010-01-08 08:40:17 +08:00
|
|
|
inline size_t dim(const Rot2&) { return 1; }
|
|
|
|
|
2010-01-11 06:41:23 +08:00
|
|
|
/** Expmap around identity - create a rotation from an angle */
|
2010-01-08 08:40:17 +08:00
|
|
|
template<> inline Rot2 expmap(const Vector& v) {
|
|
|
|
if (zero(v)) return (Rot2());
|
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
|
|
|
else return Rot2::fromAngle(v(0));
|
2010-01-08 08:40:17 +08:00
|
|
|
}
|
|
|
|
|
2010-01-11 06:41:23 +08:00
|
|
|
/** Logmap around identity - return the angle of the rotation */
|
2010-01-08 08:40:17 +08:00
|
|
|
inline Vector logmap(const Rot2& r) {
|
|
|
|
return Vector_(1, r.theta());
|
|
|
|
}
|
|
|
|
|
2010-01-11 06:41:23 +08:00
|
|
|
/** Compose - make a new rotation by adding angles */
|
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
|
|
|
inline Rot2 compose(const Rot2& R1, const Rot2& R2) { return R1*R2;}
|
2010-01-08 08:40:17 +08:00
|
|
|
|
2010-01-11 06:41:23 +08:00
|
|
|
/** The inverse rotation - negative angle */
|
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
|
|
|
inline Rot2 inverse(const Rot2& R) { return R.inverse();}
|
2009-12-15 08:00:02 +08:00
|
|
|
|
|
|
|
/**
|
|
|
|
* rotate point from rotated coordinate frame to
|
|
|
|
* world = R*p
|
|
|
|
*/
|
2010-01-15 00:57:48 +08:00
|
|
|
inline Point2 operator*(const Rot2& R, const Point2& p) {return R.rotate(p);}
|
|
|
|
Point2 rotate(const Rot2 & R, const Point2& p, boost::optional<Matrix&> H1 =
|
|
|
|
boost::none, boost::optional<Matrix&> H2 = boost::none);
|
2009-12-15 08:00:02 +08:00
|
|
|
|
|
|
|
/**
|
|
|
|
* rotate point from world to rotated
|
|
|
|
* frame = R'*p
|
|
|
|
*/
|
2010-01-15 00:57:48 +08:00
|
|
|
Point2 unrotate(const Rot2 & R, const Point2& p, boost::optional<Matrix&> H1 =
|
|
|
|
boost::none, boost::optional<Matrix&> H2 = boost::none);
|
|
|
|
|
|
|
|
/**
|
|
|
|
* Calculate relative bearing to a landmark in local coordinate frame
|
|
|
|
* @param point 2D location of landmark
|
|
|
|
* @param H optional reference for Jacobian
|
|
|
|
* @return 2D rotation \in SO(2)
|
|
|
|
*/
|
|
|
|
Rot2 relativeBearing(const Point2& d);
|
|
|
|
|
|
|
|
/**
|
|
|
|
* Calculate relative bearing and optional derivative
|
|
|
|
*/
|
|
|
|
Rot2 relativeBearing(const Point2& d, boost::optional<Matrix&> H);
|
2009-12-10 05:50:27 +08:00
|
|
|
|
|
|
|
} // gtsam
|
|
|
|
|
|
|
|
#endif /* ROT2_H_ */
|