2009-08-29 09:24:26 +08:00
|
|
|
/**
|
|
|
|
* @file testPose2.cpp
|
|
|
|
* @brief Unit tests for Pose2 class
|
|
|
|
*/
|
|
|
|
|
2009-12-09 03:12:20 +08:00
|
|
|
#include <math.h>
|
2009-08-29 09:24:26 +08:00
|
|
|
#include <CppUnitLite/TestHarness.h>
|
2009-12-22 00:43:23 +08:00
|
|
|
#include <iostream>
|
2009-12-09 03:12:20 +08:00
|
|
|
#include "numericalDerivative.h"
|
2009-08-29 09:24:26 +08:00
|
|
|
#include "Pose2.h"
|
2009-12-09 03:12:20 +08:00
|
|
|
#include "Point2.h"
|
2009-12-14 11:02:05 +08:00
|
|
|
#include "Rot2.h"
|
2009-08-29 09:24:26 +08:00
|
|
|
|
|
|
|
using namespace gtsam;
|
2009-12-22 00:43:23 +08:00
|
|
|
using namespace std;
|
|
|
|
|
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
|
|
|
// #define SLOW_BUT_CORRECT_EXPMAP
|
|
|
|
|
2009-08-29 09:24:26 +08:00
|
|
|
/* ************************************************************************* */
|
|
|
|
TEST(Pose2, constructors) {
|
2010-01-08 08:40:17 +08:00
|
|
|
//cout << "constructors" << endl;
|
2009-12-15 08:00:02 +08:00
|
|
|
Point2 p;
|
2009-12-18 08:09:54 +08:00
|
|
|
Pose2 pose(0,p);
|
2009-12-15 08:00:02 +08:00
|
|
|
Pose2 origin;
|
|
|
|
assert_equal(pose,origin);
|
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
|
|
|
Pose2 t(M_PI_2+0.018, Point2(1.015, 2.01));
|
|
|
|
CHECK(assert_equal(t,Pose2(t.matrix())));
|
2009-08-29 09:24:26 +08:00
|
|
|
}
|
|
|
|
|
2010-01-05 22:13:51 +08:00
|
|
|
/* ************************************************************************* */
|
|
|
|
TEST(Pose2, manifold) {
|
2010-01-08 08:40:17 +08:00
|
|
|
//cout << "manifold" << endl;
|
2010-01-05 22:13:51 +08:00
|
|
|
Pose2 t1(M_PI_2, Point2(1, 2));
|
|
|
|
Pose2 t2(M_PI_2+0.018, Point2(1.015, 2.01));
|
|
|
|
Pose2 origin;
|
2010-01-08 08:40:17 +08:00
|
|
|
Vector d12 = logmap(t1,t2);
|
|
|
|
CHECK(assert_equal(t2, expmap(t1,d12)));
|
2010-01-27 04:00:17 +08:00
|
|
|
CHECK(assert_equal(t2, t1*expmap(origin,d12)));
|
2010-01-08 08:40:17 +08:00
|
|
|
Vector d21 = logmap(t2,t1);
|
|
|
|
CHECK(assert_equal(t1, expmap(t2,d21)));
|
2010-01-27 04:00:17 +08:00
|
|
|
CHECK(assert_equal(t1, t2*expmap(origin,d21)));
|
2010-01-05 22:13:51 +08:00
|
|
|
}
|
|
|
|
|
2009-12-08 22:02:56 +08:00
|
|
|
/* ************************************************************************* */
|
2010-01-08 08:40:17 +08:00
|
|
|
TEST(Pose2, expmap) {
|
|
|
|
//cout << "expmap" << endl;
|
2009-12-22 00:43:23 +08:00
|
|
|
Pose2 pose(M_PI_2, Point2(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
|
|
|
#ifdef SLOW_BUT_CORRECT_EXPMAP
|
|
|
|
Pose2 expected(1.00811, 2.01528, 2.5608);
|
|
|
|
#else
|
2010-02-26 14:00:58 +08:00
|
|
|
Pose2 expected(M_PI_2+0.99, Point2(1.015, 2.01));
|
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-26 14:00:58 +08:00
|
|
|
Pose2 actual = expmap(pose, Vector_(3, 0.01, -0.015, 0.99));
|
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(expected, actual, 1e-5));
|
2009-12-08 22:02:56 +08:00
|
|
|
}
|
|
|
|
|
2009-12-22 00:43:23 +08:00
|
|
|
/* ************************************************************************* */
|
2010-02-26 14:00:58 +08:00
|
|
|
TEST(Pose2, expmap2) {
|
|
|
|
// do an actual series exponential map
|
|
|
|
// see e.g. http://www.cis.upenn.edu/~cis610/cis610lie1.ps
|
|
|
|
Matrix A = Matrix_(3,3,
|
|
|
|
0.0, -0.99, 0.01,
|
|
|
|
0.99, 0.0, -0.015,
|
|
|
|
0.0, 0.0, 0.0);
|
|
|
|
Matrix A2 = A*A/2.0, A3 = A2*A/3.0, A4=A3*A/4.0;
|
|
|
|
Matrix expected = eye(3) + A + A2 + A3 + A4;
|
|
|
|
|
|
|
|
Pose2 pose = expmap<Pose2>(Vector_(3, 0.01, -0.015, 0.99));
|
|
|
|
Matrix actual = pose.matrix();
|
|
|
|
//CHECK(assert_equal(expected, actual));
|
|
|
|
}
|
|
|
|
|
|
|
|
/* ************************************************************************* */
|
2010-01-08 08:40:17 +08:00
|
|
|
TEST(Pose2, expmap0) {
|
|
|
|
//cout << "expmap0" << endl;
|
2009-12-22 00:43:23 +08:00
|
|
|
Pose2 pose(M_PI_2, Point2(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
|
|
|
#ifdef SLOW_BUT_CORRECT_EXPMAP
|
|
|
|
Pose2 expected(1.01491, 2.01013, 1.5888);
|
|
|
|
#else
|
2009-12-22 00:43:23 +08:00
|
|
|
Pose2 expected(M_PI_2+0.018, Point2(1.015, 2.01));
|
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-01-27 04:00:17 +08:00
|
|
|
Pose2 actual = pose * expmap<Pose2>(Vector_(3, 0.01, -0.015, 0.018));
|
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(expected, actual, 1e-5));
|
|
|
|
}
|
|
|
|
|
|
|
|
#ifdef SLOW_BUT_CORRECT_EXPMAP
|
|
|
|
/* ************************************************************************* */
|
|
|
|
// test case for screw motion in the plane
|
|
|
|
namespace screw {
|
|
|
|
double w=0.3;
|
|
|
|
Vector xi = Vector_(3, 0.0, w, w);
|
|
|
|
Rot2 expectedR = Rot2::fromAngle(w);
|
|
|
|
Point2 expectedT(-0.0446635, 0.29552);
|
|
|
|
Pose2 expected(expectedR, expectedT);
|
2009-12-22 00:43:23 +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
|
|
|
TEST(Pose3, expmap_c)
|
|
|
|
{
|
|
|
|
CHECK(assert_equal(screw::expected, expm<Pose2>(screw::xi),1e-6));
|
|
|
|
CHECK(assert_equal(screw::expected, expmap<Pose2>(screw::xi),1e-6));
|
|
|
|
CHECK(assert_equal(screw::xi, logmap(screw::expected),1e-6));
|
|
|
|
}
|
|
|
|
#endif
|
|
|
|
|
2009-12-18 08:09:54 +08:00
|
|
|
/* ************************************************************************* */
|
2010-01-08 08:40:17 +08:00
|
|
|
TEST(Pose2, logmap) {
|
|
|
|
//cout << "logmap" << endl;
|
2009-12-18 08:09:54 +08:00
|
|
|
Pose2 pose0(M_PI_2, Point2(1, 2));
|
2009-12-22 00:43:23 +08:00
|
|
|
Pose2 pose(M_PI_2+0.018, Point2(1.015, 2.01));
|
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
|
|
|
|
Vector expected = Vector_(3, 0.00986473, -0.0150896, 0.018);
|
|
|
|
#else
|
2009-12-22 00:43:23 +08:00
|
|
|
Vector expected = Vector_(3, 0.01, -0.015, 0.018);
|
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-01-08 08:40:17 +08:00
|
|
|
Vector actual = logmap(pose0,pose);
|
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(expected, actual, 1e-5));
|
2009-12-18 08:09:54 +08:00
|
|
|
}
|
|
|
|
|
2009-12-09 03:12:20 +08:00
|
|
|
/* ************************************************************************* */
|
|
|
|
TEST( Pose2, transform_to )
|
|
|
|
{
|
2009-12-17 05:39:03 +08:00
|
|
|
Pose2 pose(M_PI_2, Point2(1,2)); // robot at (1,2) looking towards y
|
2009-12-15 08:00:02 +08:00
|
|
|
Point2 point(-1,4); // landmark at (-1,4)
|
2009-12-09 03:12:20 +08:00
|
|
|
|
2009-12-15 08:00:02 +08:00
|
|
|
// expected
|
|
|
|
Point2 expected(2,2);
|
2010-03-02 10:27:09 +08:00
|
|
|
Matrix expectedH1 = Matrix_(2,3, -1.0, 0.0, 2.0, 0.0, -1.0, -2.0);
|
|
|
|
Matrix expectedH2 = Matrix_(2,2, 0.0, 1.0, -1.0, 0.0);
|
2009-12-09 03:12:20 +08:00
|
|
|
|
2009-12-15 08:00:02 +08:00
|
|
|
// actual
|
2010-03-02 10:27:09 +08:00
|
|
|
Matrix actualH1, actualH2;
|
|
|
|
Point2 actual = transform_to(pose,point, actualH1, actualH2);
|
2009-12-15 08:00:02 +08:00
|
|
|
CHECK(assert_equal(expected,actual));
|
2009-12-09 03:12:20 +08:00
|
|
|
|
2010-03-02 10:27:09 +08:00
|
|
|
CHECK(assert_equal(expectedH1,actualH1));
|
2009-12-09 03:12:20 +08:00
|
|
|
Matrix numericalH1 = numericalDerivative21(transform_to, pose, point, 1e-5);
|
2009-12-15 08:00:02 +08:00
|
|
|
CHECK(assert_equal(numericalH1,actualH1));
|
2009-12-09 03:12:20 +08:00
|
|
|
|
2010-03-02 10:27:09 +08:00
|
|
|
CHECK(assert_equal(expectedH2,actualH2));
|
2009-12-09 03:12:20 +08:00
|
|
|
Matrix numericalH2 = numericalDerivative22(transform_to, pose, point, 1e-5);
|
2009-12-15 08:00:02 +08:00
|
|
|
CHECK(assert_equal(numericalH2,actualH2));
|
2009-12-09 03:12:20 +08:00
|
|
|
}
|
|
|
|
|
2010-02-28 16:51:43 +08:00
|
|
|
/* ************************************************************************* */
|
|
|
|
Point2 transform_from_proxy(const Pose2& pose, const Point2& point) {
|
|
|
|
return transform_from(pose, point);
|
|
|
|
}
|
|
|
|
|
|
|
|
TEST (Pose2, transform_from)
|
|
|
|
{
|
|
|
|
Pose2 pose(1., 0., M_PI_2);
|
|
|
|
Point2 pt(2., 1.);
|
|
|
|
Matrix H1, H2;
|
|
|
|
Point2 actual = transform_from(pose, pt, H1, H2);
|
|
|
|
|
|
|
|
Point2 expected(0., 2.);
|
|
|
|
CHECK(assert_equal(expected, actual));
|
|
|
|
|
|
|
|
Matrix H1_expected = Matrix_(2, 3, 0., -1., -2., 1., 0., -1.);
|
|
|
|
Matrix H2_expected = Matrix_(2, 2, 0., -1., 1., 0.);
|
|
|
|
|
|
|
|
Matrix numericalH1 = numericalDerivative21(transform_from_proxy, pose, pt, 1e-5);
|
|
|
|
CHECK(assert_equal(H1_expected, H1));
|
|
|
|
CHECK(assert_equal(H1_expected, numericalH1));
|
|
|
|
|
|
|
|
Matrix numericalH2 = numericalDerivative22(transform_from_proxy, pose, pt, 1e-5);
|
|
|
|
CHECK(assert_equal(H2_expected, H2));
|
|
|
|
CHECK(assert_equal(H2_expected, numericalH2));
|
|
|
|
}
|
|
|
|
|
2009-12-14 11:02:05 +08:00
|
|
|
/* ************************************************************************* */
|
|
|
|
TEST(Pose2, compose_a)
|
2009-12-22 00:43:23 +08:00
|
|
|
{
|
2010-01-08 08:40:17 +08:00
|
|
|
//cout << "compose_a" << endl;
|
2009-12-22 00:43:23 +08:00
|
|
|
Pose2 pose1(M_PI/4.0, Point2(sqrt(0.5), sqrt(0.5)));
|
|
|
|
Pose2 pose2(M_PI/2.0, Point2(0.0, 2.0));
|
|
|
|
|
2010-02-26 18:55:41 +08:00
|
|
|
Pose2 actual = compose(pose1, pose2);
|
2010-02-28 17:10:39 +08:00
|
|
|
Matrix actualDcompose1 = Dcompose1(pose1, pose2);
|
|
|
|
Matrix actualDcompose2 = Dcompose2(pose1, pose2);
|
2010-02-26 18:55:41 +08:00
|
|
|
|
2009-12-22 00:43:23 +08:00
|
|
|
Pose2 expected(3.0*M_PI/4.0, Point2(-sqrt(0.5), 3.0*sqrt(0.5)));
|
|
|
|
CHECK(assert_equal(expected, actual));
|
|
|
|
|
2010-02-26 18:55:41 +08:00
|
|
|
Matrix expectedH1 = Matrix_(3,3,
|
|
|
|
0.0, 1.0, 0.0,
|
|
|
|
-1.0, 0.0, 2.0,
|
|
|
|
0.0, 0.0, 1.0
|
|
|
|
);
|
|
|
|
Matrix expectedH2 = eye(3);
|
|
|
|
Matrix numericalH1 = numericalDerivative21<Pose2, Pose2, Pose2>(compose, pose1, pose2, 1e-5);
|
|
|
|
Matrix numericalH2 = numericalDerivative22<Pose2, Pose2, Pose2>(compose, pose1, pose2, 1e-5);
|
2010-02-28 17:10:39 +08:00
|
|
|
CHECK(assert_equal(expectedH1,actualDcompose1));
|
|
|
|
CHECK(assert_equal(numericalH1,actualDcompose1));
|
|
|
|
CHECK(assert_equal(expectedH2,actualDcompose2));
|
|
|
|
CHECK(assert_equal(numericalH2,actualDcompose2));
|
2010-02-26 18:55:41 +08:00
|
|
|
|
2009-12-22 00:43:23 +08:00
|
|
|
Point2 point(sqrt(0.5), 3.0*sqrt(0.5));
|
|
|
|
Point2 expected_point(-1.0, -1.0);
|
2010-01-27 04:00:17 +08:00
|
|
|
Point2 actual_point1 = transform_to(pose1 * pose2, point);
|
2010-01-08 08:40:17 +08:00
|
|
|
Point2 actual_point2 = transform_to(pose2, transform_to(pose1, point));
|
2009-12-22 00:43:23 +08:00
|
|
|
CHECK(assert_equal(expected_point, actual_point1));
|
|
|
|
CHECK(assert_equal(expected_point, actual_point2));
|
|
|
|
}
|
|
|
|
|
|
|
|
/* ************************************************************************* */
|
|
|
|
TEST(Pose2, compose_b)
|
2009-12-14 11:02:05 +08:00
|
|
|
{
|
2010-01-08 08:40:17 +08:00
|
|
|
//cout << "compose_b" << endl;
|
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
|
|
|
Pose2 pose1(Rot2::fromAngle(M_PI/10.0), Point2(.75, .5));
|
|
|
|
Pose2 pose2(Rot2::fromAngle(M_PI/4.0-M_PI/10.0), Point2(0.701289620636, 1.34933052585));
|
2009-12-14 11:02:05 +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
|
|
|
Pose2 pose_expected(Rot2::fromAngle(M_PI/4.0), Point2(1.0, 2.0));
|
2009-12-14 11:02:05 +08:00
|
|
|
|
2010-01-27 04:00:17 +08:00
|
|
|
Pose2 pose_actual_op = pose1 * pose2;
|
|
|
|
Pose2 pose_actual_fcn = compose(pose1, pose2);
|
2010-02-28 17:10:39 +08:00
|
|
|
Matrix actualDcompose1 = Dcompose1(pose1, pose2);
|
|
|
|
Matrix actualDcompose2 = Dcompose2(pose1, pose2);
|
2010-02-26 18:55:41 +08:00
|
|
|
|
|
|
|
Matrix numericalH1 = numericalDerivative21<Pose2, Pose2, Pose2>(compose, pose1, pose2, 1e-5);
|
|
|
|
Matrix numericalH2 = numericalDerivative22<Pose2, Pose2, Pose2>(compose, pose1, pose2, 1e-5);
|
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(numericalH1,actualDcompose1,1e-5));
|
2010-02-28 17:10:39 +08:00
|
|
|
CHECK(assert_equal(numericalH2,actualDcompose2));
|
2009-12-14 11:02:05 +08:00
|
|
|
|
|
|
|
CHECK(assert_equal(pose_expected, pose_actual_op));
|
|
|
|
CHECK(assert_equal(pose_expected, pose_actual_fcn));
|
|
|
|
}
|
|
|
|
|
|
|
|
/* ************************************************************************* */
|
2009-12-22 00:43:23 +08:00
|
|
|
TEST(Pose2, compose_c)
|
2009-12-14 11:02:05 +08:00
|
|
|
{
|
2010-01-08 08:40:17 +08:00
|
|
|
//cout << "compose_c" << endl;
|
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
|
|
|
Pose2 pose1(Rot2::fromAngle(M_PI/4.0), Point2(1.0, 1.0));
|
|
|
|
Pose2 pose2(Rot2::fromAngle(M_PI/4.0), Point2(sqrt(.5), sqrt(.5)));
|
2009-12-14 11:02:05 +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
|
|
|
Pose2 pose_expected(Rot2::fromAngle(M_PI/2.0), Point2(1.0, 2.0));
|
2009-12-14 11:02:05 +08:00
|
|
|
|
2010-01-27 04:00:17 +08:00
|
|
|
Pose2 pose_actual_op = pose1 * pose2;
|
|
|
|
Pose2 pose_actual_fcn = compose(pose1,pose2);
|
2010-02-28 17:10:39 +08:00
|
|
|
Matrix actualDcompose1 = Dcompose1(pose1, pose2);
|
|
|
|
Matrix actualDcompose2 = Dcompose2(pose1, pose2);
|
2010-02-26 18:55:41 +08:00
|
|
|
|
|
|
|
Matrix numericalH1 = numericalDerivative21<Pose2, Pose2, Pose2>(compose, pose1, pose2, 1e-5);
|
|
|
|
Matrix numericalH2 = numericalDerivative22<Pose2, Pose2, Pose2>(compose, pose1, pose2, 1e-5);
|
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(numericalH1,actualDcompose1,1e-5));
|
2010-02-28 17:10:39 +08:00
|
|
|
CHECK(assert_equal(numericalH2,actualDcompose2));
|
2009-12-14 11:02:05 +08:00
|
|
|
|
|
|
|
CHECK(assert_equal(pose_expected, pose_actual_op));
|
|
|
|
CHECK(assert_equal(pose_expected, pose_actual_fcn));
|
|
|
|
}
|
|
|
|
|
2010-01-22 13:45:59 +08:00
|
|
|
/* ************************************************************************* */
|
|
|
|
TEST(Pose2, inverse )
|
|
|
|
{
|
|
|
|
Point2 origin, t(1,2);
|
|
|
|
Pose2 gTl(M_PI_2, t); // robot at (1,2) looking towards y
|
|
|
|
|
|
|
|
Pose2 identity, lTg = inverse(gTl);
|
|
|
|
CHECK(assert_equal(identity,compose(lTg,gTl)));
|
|
|
|
CHECK(assert_equal(identity,compose(gTl,lTg)));
|
|
|
|
|
|
|
|
Point2 l(4,5), g(-4,6);
|
|
|
|
CHECK(assert_equal(g,gTl*l));
|
|
|
|
CHECK(assert_equal(l,lTg*g));
|
|
|
|
|
2010-02-28 17:10:39 +08:00
|
|
|
// Check derivative
|
|
|
|
Matrix numericalH = numericalDerivative11<Pose2,Pose2>(inverse, lTg, 1e-5);
|
|
|
|
Matrix actualDinverse = Dinverse(lTg);
|
|
|
|
CHECK(assert_equal(numericalH,actualDinverse));
|
|
|
|
}
|
2010-01-22 13:45:59 +08:00
|
|
|
|
|
|
|
/* ************************************************************************* */
|
|
|
|
Vector homogeneous(const Point2& p) {
|
|
|
|
return Vector_(3, p.x(), p.y(), 1.0);
|
|
|
|
}
|
|
|
|
|
|
|
|
Matrix matrix(const Pose2& gTl) {
|
|
|
|
Matrix gRl = gTl.r().matrix();
|
|
|
|
Point2 gt = gTl.t();
|
|
|
|
return Matrix_(3, 3,
|
|
|
|
gRl(0, 0), gRl(0, 1), gt.x(),
|
|
|
|
gRl(1, 0), gRl(1, 1), gt.y(),
|
|
|
|
0.0, 0.0, 1.0);
|
|
|
|
}
|
|
|
|
|
|
|
|
TEST( Pose2, matrix )
|
|
|
|
{
|
|
|
|
Point2 origin, t(1,2);
|
2010-01-23 01:36:57 +08:00
|
|
|
Pose2 gTl(M_PI_2, t); // robot at (1,2) looking towards y
|
|
|
|
Matrix gMl = matrix(gTl);
|
2010-01-22 13:45:59 +08:00
|
|
|
CHECK(assert_equal(Matrix_(3,3,
|
|
|
|
0.0, -1.0, 1.0,
|
|
|
|
1.0, 0.0, 2.0,
|
|
|
|
0.0, 0.0, 1.0),
|
2010-01-23 01:36:57 +08:00
|
|
|
gMl));
|
|
|
|
Rot2 gR1 = gTl.r();
|
|
|
|
CHECK(assert_equal(homogeneous(t),gMl*homogeneous(origin)));
|
2010-01-22 13:45:59 +08:00
|
|
|
Point2 x_axis(1,0), y_axis(0,1);
|
|
|
|
CHECK(assert_equal(Matrix_(2,2,
|
|
|
|
0.0, -1.0,
|
|
|
|
1.0, 0.0),
|
|
|
|
gR1.matrix()));
|
|
|
|
CHECK(assert_equal(Point2(0,1),gR1*x_axis));
|
|
|
|
CHECK(assert_equal(Point2(-1,0),gR1*y_axis));
|
2010-01-23 01:36:57 +08:00
|
|
|
CHECK(assert_equal(homogeneous(Point2(1+0,2+1)),gMl*homogeneous(x_axis)));
|
|
|
|
CHECK(assert_equal(homogeneous(Point2(1-1,2+0)),gMl*homogeneous(y_axis)));
|
2010-01-22 13:45:59 +08:00
|
|
|
|
|
|
|
// check inverse pose
|
2010-01-23 01:36:57 +08:00
|
|
|
Matrix lMg = matrix(inverse(gTl));
|
|
|
|
CHECK(assert_equal(Matrix_(3,3,
|
|
|
|
0.0, 1.0,-2.0,
|
|
|
|
-1.0, 0.0, 1.0,
|
|
|
|
0.0, 0.0, 1.0),
|
|
|
|
lMg));
|
|
|
|
}
|
|
|
|
|
|
|
|
/* ************************************************************************* */
|
|
|
|
TEST( Pose2, compose_matrix )
|
|
|
|
{
|
|
|
|
Pose2 gT1(M_PI_2, Point2(1,2)); // robot at (1,2) looking towards y
|
|
|
|
Pose2 _1T2(M_PI, Point2(-1,4)); // local robot at (-1,4) loooking at negative x
|
|
|
|
Matrix gM1(matrix(gT1)),_1M2(matrix(_1T2));
|
2010-01-27 04:00:17 +08:00
|
|
|
CHECK(assert_equal(gM1*_1M2,matrix(compose(gT1,_1T2)))); // RIGHT DOES NOT
|
2010-01-22 13:45:59 +08:00
|
|
|
}
|
2009-12-14 11:02:05 +08:00
|
|
|
|
2009-12-09 03:12:20 +08:00
|
|
|
/* ************************************************************************* */
|
|
|
|
TEST( Pose2, between )
|
|
|
|
{
|
2010-01-16 09:16:59 +08:00
|
|
|
// <
|
|
|
|
//
|
|
|
|
// ^
|
|
|
|
//
|
|
|
|
// *--0--*--*
|
2010-01-22 13:45:59 +08:00
|
|
|
Pose2 gT1(M_PI_2, Point2(1,2)); // robot at (1,2) looking towards y
|
|
|
|
Pose2 gT2(M_PI, Point2(-1,4)); // robot at (-1,4) loooking at negative x
|
2009-12-15 08:00:02 +08:00
|
|
|
|
2010-01-16 09:16:59 +08:00
|
|
|
Matrix actualH1,actualH2;
|
2009-12-17 05:39:03 +08:00
|
|
|
Pose2 expected(M_PI_2, Point2(2,2));
|
2010-02-28 17:10:39 +08:00
|
|
|
Pose2 actual1 = between(gT1,gT2);
|
2010-01-22 13:45:59 +08:00
|
|
|
Pose2 actual2 = between(gT1,gT2,actualH1,actualH2);
|
2010-01-16 09:16:59 +08:00
|
|
|
CHECK(assert_equal(expected,actual1));
|
|
|
|
CHECK(assert_equal(expected,actual2));
|
2010-01-08 08:40:17 +08:00
|
|
|
|
2009-12-15 08:00:02 +08:00
|
|
|
Matrix expectedH1 = Matrix_(3,3,
|
2009-12-22 00:43:23 +08:00
|
|
|
0.0,-1.0,-2.0,
|
|
|
|
1.0, 0.0,-2.0,
|
|
|
|
0.0, 0.0,-1.0
|
2009-12-15 08:00:02 +08:00
|
|
|
);
|
2010-01-22 13:45:59 +08:00
|
|
|
Matrix numericalH1 = numericalDerivative21(between<Pose2>, gT1, gT2, 1e-5);
|
2010-01-08 08:40:17 +08:00
|
|
|
CHECK(assert_equal(expectedH1,actualH1));
|
|
|
|
CHECK(assert_equal(numericalH1,actualH1));
|
2010-02-28 17:10:39 +08:00
|
|
|
// Assert H1 = -AdjointMap(between(p2,p1)) as in doc/math.lyx
|
|
|
|
CHECK(assert_equal(-AdjointMap(between(gT2,gT1)),actualH1));
|
2010-01-08 08:40:17 +08:00
|
|
|
|
2009-12-15 08:00:02 +08:00
|
|
|
Matrix expectedH2 = Matrix_(3,3,
|
2009-12-22 00:43:23 +08:00
|
|
|
1.0, 0.0, 0.0,
|
|
|
|
0.0, 1.0, 0.0,
|
|
|
|
0.0, 0.0, 1.0
|
2009-12-15 08:00:02 +08:00
|
|
|
);
|
2010-01-22 13:45:59 +08:00
|
|
|
Matrix numericalH2 = numericalDerivative22(between<Pose2>, gT1, gT2, 1e-5);
|
2009-12-15 08:00:02 +08:00
|
|
|
CHECK(assert_equal(expectedH2,actualH2));
|
|
|
|
CHECK(assert_equal(numericalH2,actualH2));
|
2010-02-28 17:10:39 +08:00
|
|
|
|
2009-12-09 03:12:20 +08:00
|
|
|
}
|
|
|
|
|
2010-01-16 09:16:59 +08:00
|
|
|
/* ************************************************************************* */
|
|
|
|
// reverse situation for extra test
|
|
|
|
TEST( Pose2, between2 )
|
|
|
|
{
|
|
|
|
Pose2 p2(M_PI_2, Point2(1,2)); // robot at (1,2) looking towards y
|
|
|
|
Pose2 p1(M_PI, Point2(-1,4)); // robot at (-1,4) loooking at negative x
|
|
|
|
|
|
|
|
Matrix actualH1,actualH2;
|
|
|
|
between(p1,p2,actualH1,actualH2);
|
|
|
|
Matrix numericalH1 = numericalDerivative21(between<Pose2>, p1, p2, 1e-5);
|
|
|
|
CHECK(assert_equal(numericalH1,actualH1));
|
|
|
|
Matrix numericalH2 = numericalDerivative22(between<Pose2>, p1, p2, 1e-5);
|
|
|
|
CHECK(assert_equal(numericalH2,actualH2));
|
|
|
|
}
|
|
|
|
|
2010-01-13 14:02:18 +08:00
|
|
|
/* ************************************************************************* */
|
|
|
|
TEST( Pose2, round_trip )
|
|
|
|
{
|
|
|
|
Pose2 p1(1.23, 2.30, 0.2);
|
|
|
|
Pose2 odo(0.53, 0.39, 0.15);
|
2010-01-27 04:00:17 +08:00
|
|
|
Pose2 p2 = compose(p1, odo);
|
2010-01-13 14:02:18 +08:00
|
|
|
CHECK(assert_equal(odo, between(p1, p2)));
|
|
|
|
}
|
|
|
|
|
2010-01-10 07:15:06 +08:00
|
|
|
/* ************************************************************************* */
|
|
|
|
TEST(Pose2, members)
|
|
|
|
{
|
|
|
|
Pose2 pose;
|
|
|
|
CHECK(pose.dim() == 3);
|
|
|
|
}
|
|
|
|
|
2010-01-16 09:16:59 +08:00
|
|
|
/* ************************************************************************* */
|
|
|
|
// some shared test values
|
|
|
|
Pose2 x1, x2(1, 1, 0), x3(1, 1, M_PI_4);
|
|
|
|
Point2 l1(1, 0), l2(1, 1), l3(2, 2), l4(1, 3);
|
|
|
|
|
|
|
|
/* ************************************************************************* */
|
|
|
|
TEST( Pose2, bearing )
|
|
|
|
{
|
|
|
|
Matrix expectedH1, actualH1, expectedH2, actualH2;
|
|
|
|
|
|
|
|
// establish bearing is indeed zero
|
|
|
|
CHECK(assert_equal(Rot2(),bearing(x1,l1)));
|
|
|
|
|
|
|
|
// establish bearing is indeed 45 degrees
|
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),bearing(x1,l2)));
|
2010-01-16 09:16:59 +08:00
|
|
|
|
|
|
|
// establish bearing is indeed 45 degrees even if shifted
|
|
|
|
Rot2 actual23 = bearing(x2, l3, actualH1, actualH2);
|
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),actual23));
|
2010-01-16 09:16:59 +08:00
|
|
|
|
|
|
|
// Check numerical derivatives
|
|
|
|
expectedH1 = numericalDerivative21(bearing, x2, l3, 1e-5);
|
|
|
|
CHECK(assert_equal(expectedH1,actualH1));
|
|
|
|
expectedH2 = numericalDerivative22(bearing, x2, l3, 1e-5);
|
|
|
|
CHECK(assert_equal(expectedH1,actualH1));
|
|
|
|
|
|
|
|
// establish bearing is indeed 45 degrees even if rotated
|
|
|
|
Rot2 actual34 = bearing(x3, l4, actualH1, actualH2);
|
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),actual34));
|
2010-01-16 09:16:59 +08:00
|
|
|
|
|
|
|
// Check numerical derivatives
|
|
|
|
expectedH1 = numericalDerivative21(bearing, x3, l4, 1e-5);
|
|
|
|
expectedH2 = numericalDerivative22(bearing, x3, l4, 1e-5);
|
|
|
|
CHECK(assert_equal(expectedH1,actualH1));
|
|
|
|
CHECK(assert_equal(expectedH1,actualH1));
|
|
|
|
}
|
|
|
|
|
|
|
|
/* ************************************************************************* */
|
|
|
|
TEST( Pose2, range )
|
|
|
|
{
|
|
|
|
Matrix expectedH1, actualH1, expectedH2, actualH2;
|
|
|
|
|
|
|
|
// establish range is indeed zero
|
|
|
|
DOUBLES_EQUAL(1,gtsam::range(x1,l1),1e-9);
|
|
|
|
|
|
|
|
// establish range is indeed 45 degrees
|
|
|
|
DOUBLES_EQUAL(sqrt(2),gtsam::range(x1,l2),1e-9);
|
|
|
|
|
|
|
|
// Another pair
|
|
|
|
double actual23 = gtsam::range(x2, l3, actualH1, actualH2);
|
|
|
|
DOUBLES_EQUAL(sqrt(2),actual23,1e-9);
|
|
|
|
|
|
|
|
// Check numerical derivatives
|
|
|
|
expectedH1 = numericalDerivative21(range, x2, l3, 1e-5);
|
|
|
|
CHECK(assert_equal(expectedH1,actualH1));
|
|
|
|
expectedH2 = numericalDerivative22(range, x2, l3, 1e-5);
|
|
|
|
CHECK(assert_equal(expectedH1,actualH1));
|
|
|
|
|
|
|
|
// Another test
|
|
|
|
double actual34 = gtsam::range(x3, l4, actualH1, actualH2);
|
|
|
|
DOUBLES_EQUAL(2,actual34,1e-9);
|
|
|
|
|
|
|
|
// Check numerical derivatives
|
|
|
|
expectedH1 = numericalDerivative21(range, x3, l4, 1e-5);
|
|
|
|
expectedH2 = numericalDerivative22(range, x3, l4, 1e-5);
|
|
|
|
CHECK(assert_equal(expectedH1,actualH1));
|
|
|
|
CHECK(assert_equal(expectedH1,actualH1));
|
|
|
|
}
|
|
|
|
|
2009-08-29 09:24:26 +08:00
|
|
|
/* ************************************************************************* */
|
|
|
|
int main() {
|
2009-12-15 08:00:02 +08:00
|
|
|
TestResult tr;
|
|
|
|
return TestRegistry::runAllTests(tr);
|
2009-08-29 09:24:26 +08:00
|
|
|
}
|
|
|
|
/* ************************************************************************* */
|
|
|
|
|