testEvent.cpp
Go to the documentation of this file.
1 /* ----------------------------------------------------------------------------
2 
3  * GTSAM Copyright 2010, Georgia Tech Research Corporation,
4  * Atlanta, Georgia 30332-0415
5  * All Rights Reserved
6  * Authors: Frank Dellaert, et al. (see THANKS for the full author list)
7 
8  * See LICENSE for the license information
9 
10  * -------------------------------------------------------------------------- */
11 
23 
25 
26 #include <boost/bind.hpp>
27 
28 using namespace std;
29 using namespace gtsam;
30 
31 // Create a noise model for the TOA error
32 static const double ms = 1e-3;
33 static const double cm = 1e-2;
35 static SharedNoiseModel model(noiseModel::Isotropic::Sigma(1, 0.5 * ms));
36 
37 static const double timeOfEvent = 25;
38 static const Event exampleEvent(timeOfEvent, 1, 0, 0);
39 static const Point3 microphoneAt0(0, 0, 0);
40 
41 static const double kSpeedOfSound = 340;
42 static const TimeOfArrival kToa(kSpeedOfSound);
43 
44 //*****************************************************************************
45 TEST(Event, Constructor) {
46  const double t = 0;
47  Event actual(t, 201.5 * cm, 201.5 * cm, (212 - 45) * cm);
48 }
49 
50 //*****************************************************************************
51 TEST(Event, Toa1) {
52  Event event(0, 1, 0, 0);
53  double expected = 1. / kSpeedOfSound;
54  EXPECT_DOUBLES_EQUAL(expected, kToa(event, microphoneAt0), 1e-9);
55 }
56 
57 //*****************************************************************************
58 TEST(Event, Toa2) {
59  double expectedTOA = timeOfEvent + 1. / kSpeedOfSound;
61 }
62 
63 //*************************************************************************
64 TEST(Event, Derivatives) {
65  Matrix14 actualH1;
66  Matrix13 actualH2;
67  kToa(exampleEvent, microphoneAt0, actualH1, actualH2);
68  Matrix expectedH1 = numericalDerivative11<double, Event>(
69  boost::bind(kToa, _1, microphoneAt0, boost::none, boost::none),
70  exampleEvent);
71  EXPECT(assert_equal(expectedH1, actualH1, 1e-8));
72  Matrix expectedH2 = numericalDerivative11<double, Point3>(
73  boost::bind(kToa, exampleEvent, _1, boost::none, boost::none),
75  EXPECT(assert_equal(expectedH2, actualH2, 1e-8));
76 }
77 
78 //*****************************************************************************
80  Key key = 12;
81  Expression<Event> event_(key);
82  Expression<Point3> knownMicrophone_(microphoneAt0); // constant expression
83  Expression<double> expression(kToa, event_, knownMicrophone_);
84 
85  Values values;
86  values.insert(key, exampleEvent);
87  double expectedTOA = timeOfEvent + 1. / kSpeedOfSound;
88  EXPECT_DOUBLES_EQUAL(expectedTOA, expression.value(values), 1e-9);
89 }
90 
91 //*****************************************************************************
92 TEST(Event, Retract) {
93  Event event, expected(1, 2, 3, 4);
94  Vector4 v;
95  v << 1, 2, 3, 4;
96  EXPECT(assert_equal(expected, event.retract(v)));
97 }
98 
99 //*****************************************************************************
100 int main() {
101  TestResult tr;
102  return TestRegistry::runAllTests(tr);
103 }
104 //*****************************************************************************
TEST(Event, Constructor)
Definition: testEvent.cpp:45
static const double ms
Definition: testEvent.cpp:32
static int runAllTests(TestResult &result)
Event retract(const Vector4 &v) const
Updates a with tangent space delta.
Definition: Event.h:72
Eigen::Matrix< double, 1, 1 > Vector1
Definition: testEvent.cpp:34
void insert(Key j, const Value &val)
Definition: Values.cpp:140
Matrix expected
Definition: testMatrix.cpp:974
ArrayXcf v
Definition: Cwise_arg.cpp:1
Eigen::MatrixXd Matrix
Definition: base/Matrix.h:43
leaf::MyValues values
Definition: Half.h:150
Some functions to compute numerical derivatives.
#define EXPECT_DOUBLES_EQUAL(expected, actual, threshold)
Definition: Test.h:162
Expressions for Block Automatic Differentiation.
static const Event exampleEvent(timeOfEvent, 1, 0, 0)
static const Point3 microphoneAt0(0, 0, 0)
#define EXPECT(condition)
Definition: Test.h:151
Array< double, 1, 3 > e(1./3., 0.5, 2.)
traits
Definition: chartTesting.h:28
Time of arrival to given sensor.
Definition: Event.h:87
static SharedNoiseModel model(noiseModel::Isotropic::Sigma(1, 0.5 *ms))
bool assert_equal(const Matrix &expected, const Matrix &actual, double tol)
Definition: Matrix.cpp:42
T value(const Values &values, boost::optional< std::vector< Matrix > & > H=boost::none) const
Return value and optional derivatives, reverse AD version Notes: this is not terribly efficient...
static const TimeOfArrival kToa(kSpeedOfSound)
Vector3 Point3
Definition: Point3.h:35
The matrix class, also used for vectors and row-vectors.
static const double kSpeedOfSound
Definition: testEvent.cpp:41
static const double timeOfEvent
Definition: testEvent.cpp:37
static const double cm
Definition: testEvent.cpp:33
int main()
Definition: testEvent.cpp:100
std::uint64_t Key
Integer nonlinear key type.
Definition: types.h:61
Point2 t(10, 10)
noiseModel::Base::shared_ptr SharedNoiseModel
Definition: NoiseModel.h:734


gtsam
Author(s):
autogenerated on Sat May 8 2021 02:46:32