2009-12-10 05:50:27 +08:00
|
|
|
/**
|
|
|
|
* @file testRot2.cpp
|
|
|
|
* @brief Unit tests for Rot2 class
|
|
|
|
* @author Frank Dellaert
|
|
|
|
*/
|
|
|
|
|
|
|
|
#include <CppUnitLite/TestHarness.h>
|
|
|
|
#include "numericalDerivative.h"
|
|
|
|
#include "Rot2.h"
|
|
|
|
|
|
|
|
using namespace gtsam;
|
|
|
|
|
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 R(Rot2::fromAngle(0.1));
|
2009-12-10 05:50:27 +08:00
|
|
|
Point2 P(0.2, 0.7);
|
|
|
|
|
|
|
|
/* ************************************************************************* */
|
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
|
|
|
TEST( Rot2, constructors_and_angle)
|
2009-12-10 05:50:27 +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
|
|
|
double c=cos(0.1), s=sin(0.1);
|
2009-12-18 08:09:54 +08:00
|
|
|
DOUBLES_EQUAL(0.1,R.theta(),1e-9);
|
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
|
|
|
CHECK(assert_equal(R,Rot2::fromCosSin(c,s)));
|
|
|
|
CHECK(assert_equal(R,Rot2::atan2(s*5,c*5)));
|
2009-12-10 05:50:27 +08:00
|
|
|
}
|
|
|
|
|
|
|
|
/* ************************************************************************* */
|
|
|
|
TEST( Rot2, transpose)
|
|
|
|
{
|
2010-01-08 08:40:17 +08:00
|
|
|
CHECK(assert_equal(inverse(R).matrix(),R.transpose()));
|
2009-12-10 05:50:27 +08:00
|
|
|
}
|
|
|
|
|
2009-12-14 23:45:45 +08:00
|
|
|
/* ************************************************************************* */
|
|
|
|
TEST( Rot2, compose)
|
|
|
|
{
|
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
|
|
|
CHECK(assert_equal(Rot2::fromAngle(0.45), Rot2::fromAngle(0.2)*Rot2::fromAngle(0.25)));
|
|
|
|
CHECK(assert_equal(Rot2::fromAngle(0.45), Rot2::fromAngle(0.25)*Rot2::fromAngle(0.2)));
|
2009-12-14 23:45:45 +08:00
|
|
|
}
|
|
|
|
|
2009-12-10 05:50:27 +08:00
|
|
|
/* ************************************************************************* */
|
|
|
|
TEST( Rot2, equals)
|
|
|
|
{
|
|
|
|
CHECK(R.equals(R));
|
|
|
|
Rot2 zero;
|
|
|
|
CHECK(!R.equals(zero));
|
|
|
|
}
|
|
|
|
|
|
|
|
/* ************************************************************************* */
|
2010-01-08 08:40:17 +08:00
|
|
|
TEST( Rot2, expmap)
|
2009-12-10 05:50:27 +08:00
|
|
|
{
|
|
|
|
Vector v = zero(1);
|
2010-01-08 08:40:17 +08:00
|
|
|
CHECK(assert_equal(expmap(R,v), R));
|
2009-12-10 05:50:27 +08:00
|
|
|
}
|
|
|
|
|
2009-12-18 08:09:54 +08:00
|
|
|
/* ************************************************************************* */
|
2010-01-08 08:40:17 +08:00
|
|
|
TEST(Rot2, logmap)
|
2009-12-18 08:09:54 +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
|
|
|
Rot2 rot0(Rot2::fromAngle(M_PI_2));
|
|
|
|
Rot2 rot(Rot2::fromAngle(M_PI));
|
2010-01-15 00:57:48 +08:00
|
|
|
Vector expected = Vector_(1, M_PI_2);
|
|
|
|
Vector actual = logmap(rot0, rot);
|
|
|
|
CHECK(assert_equal(expected, actual));
|
2009-12-18 08:09:54 +08:00
|
|
|
}
|
|
|
|
|
2009-12-10 05:50:27 +08:00
|
|
|
/* ************************************************************************* */
|
2010-01-15 00:57:48 +08:00
|
|
|
// rotate and derivatives
|
|
|
|
inline Point2 rotate_(const Rot2 & R, const Point2& p) {return R.rotate(p);}
|
|
|
|
TEST( Rot2, rotate)
|
2009-12-10 05:50:27 +08:00
|
|
|
{
|
2010-01-15 00:57:48 +08:00
|
|
|
Matrix H1, H2;
|
|
|
|
Point2 actual = rotate(R, P, H1, H2);
|
|
|
|
CHECK(assert_equal(actual,R*P));
|
|
|
|
Matrix numerical1 = numericalDerivative21(rotate_, R, P);
|
|
|
|
CHECK(assert_equal(numerical1,H1));
|
|
|
|
Matrix numerical2 = numericalDerivative22(rotate_, R, P);
|
|
|
|
CHECK(assert_equal(numerical2,H2));
|
2009-12-10 05:50:27 +08:00
|
|
|
}
|
|
|
|
|
|
|
|
/* ************************************************************************* */
|
2010-01-15 00:57:48 +08:00
|
|
|
// unrotate and derivatives
|
|
|
|
inline Point2 unrotate_(const Rot2 & R, const Point2& p) {return R.unrotate(p);}
|
2009-12-10 05:50:27 +08:00
|
|
|
TEST( Rot2, unrotate)
|
|
|
|
{
|
2010-01-15 00:57:48 +08:00
|
|
|
Matrix H1, H2;
|
|
|
|
Point2 w = R * P, actual = unrotate(R, w, H1, H2);
|
|
|
|
CHECK(assert_equal(actual,P));
|
|
|
|
Matrix numerical1 = numericalDerivative21(unrotate_, R, w);
|
|
|
|
CHECK(assert_equal(numerical1,H1));
|
|
|
|
Matrix numerical2 = numericalDerivative22(unrotate_, R, w);
|
|
|
|
CHECK(assert_equal(numerical2,H2));
|
2009-12-10 05:50:27 +08:00
|
|
|
}
|
|
|
|
|
2010-01-16 09:16:59 +08:00
|
|
|
/* ************************************************************************* */
|
|
|
|
TEST( Rot2, relativeBearing )
|
|
|
|
{
|
|
|
|
Point2 l1(1, 0), l2(1, 1);
|
|
|
|
Matrix expectedH, actualH;
|
|
|
|
|
|
|
|
// establish relativeBearing is indeed zero
|
|
|
|
Rot2 actual1 = relativeBearing(l1, actualH);
|
|
|
|
CHECK(assert_equal(Rot2(),actual1));
|
|
|
|
|
|
|
|
// Check numerical derivative
|
|
|
|
expectedH = numericalDerivative11(relativeBearing, l1, 1e-5);
|
|
|
|
CHECK(assert_equal(expectedH,actualH));
|
|
|
|
|
|
|
|
// establish relativeBearing is indeed 45 degrees
|
|
|
|
Rot2 actual2 = relativeBearing(l2, actualH);
|
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
|
|
|
CHECK(assert_equal(Rot2::fromAngle(M_PI_4),actual2));
|
2010-01-16 09:16:59 +08:00
|
|
|
|
|
|
|
// Check numerical derivative
|
|
|
|
expectedH = numericalDerivative11(relativeBearing, l2, 1e-5);
|
|
|
|
CHECK(assert_equal(expectedH,actualH));
|
|
|
|
}
|
|
|
|
|
2009-12-10 05:50:27 +08:00
|
|
|
/* ************************************************************************* */
|
|
|
|
int main() {
|
|
|
|
TestResult tr;
|
|
|
|
return TestRegistry::runAllTests(tr);
|
|
|
|
}
|
|
|
|
/* ************************************************************************* */
|
|
|
|
|