2010-10-14 12:54:38 +08:00
|
|
|
/* ----------------------------------------------------------------------------
|
|
|
|
|
2019-02-11 22:39:48 +08:00
|
|
|
* GTSAM Copyright 2010, Georgia Tech Research Corporation,
|
2010-10-14 12:54:38 +08:00
|
|
|
* Atlanta, Georgia 30332-0415
|
|
|
|
* All Rights Reserved
|
|
|
|
* Authors: Frank Dellaert, et al. (see THANKS for the full author list)
|
|
|
|
|
|
|
|
* See LICENSE for the license information
|
|
|
|
|
|
|
|
* -------------------------------------------------------------------------- */
|
|
|
|
|
2009-08-22 06:23:24 +08:00
|
|
|
/**
|
|
|
|
* @file testSimulated2D.cpp
|
|
|
|
* @brief Unit tests for simulated 2D measurement functions
|
|
|
|
* @author Christian Potthast
|
|
|
|
* @author Carlos Nieto
|
|
|
|
**/
|
|
|
|
|
|
|
|
#include <iostream>
|
2010-10-26 04:10:33 +08:00
|
|
|
#include <CppUnitLite/TestHarness.h>
|
2009-08-22 06:23:24 +08:00
|
|
|
|
2011-10-20 10:11:28 +08:00
|
|
|
#include <gtsam/base/Testable.h>
|
2010-08-20 01:23:19 +08:00
|
|
|
#include <gtsam/base/numericalDerivative.h>
|
2012-06-10 04:15:44 +08:00
|
|
|
#include <tests/simulated2D.h>
|
2009-08-22 06:23:24 +08:00
|
|
|
|
|
|
|
using namespace std;
|
2011-11-07 03:08:42 +08:00
|
|
|
using namespace gtsam;
|
2012-01-31 06:00:13 +08:00
|
|
|
using namespace simulated2D;
|
2009-08-22 06:23:24 +08:00
|
|
|
|
2010-02-23 13:06:16 +08:00
|
|
|
/* ************************************************************************* */
|
2010-10-09 11:09:58 +08:00
|
|
|
TEST( simulated2D, Simulated2DValues )
|
2010-02-23 13:06:16 +08:00
|
|
|
{
|
2012-10-02 22:40:07 +08:00
|
|
|
simulated2D::Values actual;
|
|
|
|
actual.insert(1,Point2(1,1));
|
|
|
|
actual.insert(2,Point2(2,2));
|
2011-11-07 03:08:42 +08:00
|
|
|
EXPECT(assert_equal(actual,actual,1e-9));
|
2010-02-23 13:06:16 +08:00
|
|
|
}
|
|
|
|
|
2009-08-22 06:23:24 +08:00
|
|
|
/* ************************************************************************* */
|
|
|
|
TEST( simulated2D, Dprior )
|
|
|
|
{
|
2010-01-19 13:33:44 +08:00
|
|
|
Point2 x(1,-9);
|
2011-11-07 03:08:42 +08:00
|
|
|
Matrix numerical = numericalDerivative11(simulated2D::prior,x);
|
2010-01-14 10:50:06 +08:00
|
|
|
Matrix computed;
|
2011-11-07 03:08:42 +08:00
|
|
|
simulated2D::prior(x,computed);
|
|
|
|
EXPECT(assert_equal(numerical,computed,1e-9));
|
2009-08-22 06:23:24 +08:00
|
|
|
}
|
|
|
|
|
|
|
|
/* ************************************************************************* */
|
2010-01-14 10:50:06 +08:00
|
|
|
TEST( simulated2D, DOdo )
|
2009-08-22 06:23:24 +08:00
|
|
|
{
|
2010-01-19 13:33:44 +08:00
|
|
|
Point2 x1(1,-9),x2(-5,6);
|
2010-01-14 10:50:06 +08:00
|
|
|
Matrix H1,H2;
|
2011-11-07 03:08:42 +08:00
|
|
|
simulated2D::odo(x1,x2,H1,H2);
|
|
|
|
Matrix A1 = numericalDerivative21(simulated2D::odo,x1,x2);
|
|
|
|
EXPECT(assert_equal(A1,H1,1e-9));
|
|
|
|
Matrix A2 = numericalDerivative22(simulated2D::odo,x1,x2);
|
|
|
|
EXPECT(assert_equal(A2,H2,1e-9));
|
2009-08-22 06:23:24 +08:00
|
|
|
}
|
|
|
|
|
|
|
|
/* ************************************************************************* */
|
|
|
|
int main() { TestResult tr; return TestRegistry::runAllTests(tr);}
|
|
|
|
/* ************************************************************************* */
|