testTOAFactor.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 
26 
28 
29 using namespace std;
30 using namespace gtsam;
31 
32 // typedefs
35 
36 // units
37 static const double ms = 1e-3;
38 static const double cm = 1e-2;
39 
40 // Create a noise model for the TOA error
41 static SharedNoiseModel model(noiseModel::Isotropic::Sigma(1, 0.5 * ms));
42 
43 static const double timeOfEvent = 25;
44 static const Event exampleEvent(timeOfEvent, 1, 0, 0);
45 static const Point3 sensorAt0(0, 0, 0);
46 
47 //*****************************************************************************
48 TEST(TOAFactor, NewWay) {
49  Key key = 12;
50  double measurement = 7;
52 }
53 
54 //*****************************************************************************
55 TEST(TOAFactor, WholeEnchilada) {
56  // Create sensors
57  const double height = 0.5;
58  vector<Point3> sensors;
59  sensors.push_back(Point3(0, 0, height));
60  sensors.push_back(Point3(403 * cm, 0, height));
61  sensors.push_back(Point3(403 * cm, 403 * cm, height));
62  sensors.push_back(Point3(0, 403 * cm, 2 * height));
63  EXPECT_LONGS_EQUAL(4, sensors.size());
64  // sensors.push_back(Point3(200 * cm, 200 * cm, height));
65 
66  // Create a ground truth point
67  const double timeOfEvent = 0;
68  Event groundTruthEvent(timeOfEvent, 245 * cm, 201.5 * cm, (212 - 45) * cm);
69 
70  // Simulate simulatedTOA
71  size_t K = sensors.size();
72  vector<double> simulatedTOA(K);
73  TimeOfArrival toa;
74  for (size_t i = 0; i < K; i++) {
75  simulatedTOA[i] = toa(groundTruthEvent, sensors[i]);
76  }
77 
78  // Now, estimate using non-linear optimization
80  Key key = 12;
81  for (size_t i = 0; i < K; i++) {
82  graph.emplace_shared<TOAFactor>(key, sensors[i], simulatedTOA[i], model);
83  }
84 
85  // Create initial estimate
86  Values initialEstimate;
87  // Event estimatedEvent(timeOfEvent -10, 200 * cm, 150 * cm, 350 * cm);
88  Vector4 delta;
89  delta << 0.1, 0.1, -0.1, 0.1;
90  Event estimatedEvent = groundTruthEvent.retract(delta);
91  initialEstimate.insert(key, estimatedEvent);
92 
93  // Optimize using Levenberg-Marquardt optimization.
95  params.setAbsoluteErrorTol(1e-10);
96  LevenbergMarquardtOptimizer optimizer(graph, initialEstimate, params);
97  Values result = optimizer.optimize();
98 
99  EXPECT(assert_equal(groundTruthEvent, result.at<Event>(key), 1e-6));
100 }
101 //*****************************************************************************
102 int main() {
103  TestResult tr;
104  return TestRegistry::runAllTests(tr);
105 }
106 //*****************************************************************************
TestRegistry::runAllTests
static int runAllTests(TestResult &result)
Definition: TestRegistry.cpp:27
sensorAt0
static const Point3 sensorAt0(0, 0, 0)
gtsam::NonlinearOptimizer::optimize
virtual const Values & optimize()
Definition: NonlinearOptimizer.h:98
e
Array< double, 1, 3 > e(1./3., 0.5, 2.)
cm
static const double cm
Definition: testTOAFactor.cpp:38
EXPECT_LONGS_EQUAL
#define EXPECT_LONGS_EQUAL(expected, actual)
Definition: Test.h:154
EXPECT
#define EXPECT(condition)
Definition: Test.h:150
TestHarness.h
LevenbergMarquardtOptimizer.h
A nonlinear optimizer that uses the Levenberg-Marquardt trust-region scheme.
vanilla::params
static const SmartProjectionParams params
Definition: smartFactorScenarios.h:69
gtsam::TimeOfArrival
Time of arrival to given sensor.
Definition: Event.h:87
result
Values result
Definition: OdometryOptimize.cpp:8
Point3_
Expression< Point3 > Point3_
Definition: testTOAFactor.cpp:33
gtsam::Expression
Definition: Expression.h:47
gtsam::Values::at
const ValueType at(Key j) const
Definition: Values-inl.h:261
model
static SharedNoiseModel model(noiseModel::Isotropic::Sigma(1, 0.5 *ms))
numericalDerivative.h
Some functions to compute numerical derivatives.
expressions.h
Common expressions, both linear and non-linear.
gtsam::Event::retract
Event retract(const Vector4 &v) const
Updates a with tangent space delta.
Definition: Event.h:72
gtsam.examples.PlanarManipulatorExample.delta
def delta(g0, g1)
Definition: PlanarManipulatorExample.py:45
TEST
TEST(TOAFactor, NewWay)
Definition: testTOAFactor.cpp:48
exampleEvent
static const Event exampleEvent(timeOfEvent, 1, 0, 0)
gtsam::NonlinearFactorGraph
Definition: NonlinearFactorGraph.h:55
gtsam::TOAFactor
A "Time of Arrival" factor - so little code seems hardly worth it :-)
Definition: TOAFactor.h:28
gtsam::LevenbergMarquardtOptimizer
Definition: LevenbergMarquardtOptimizer.h:35
gtsam::SharedNoiseModel
noiseModel::Base::shared_ptr SharedNoiseModel
Definition: NoiseModel.h:741
Event.h
Space-time event.
main
int main()
Definition: testTOAFactor.cpp:102
gtsam::Event
Definition: Event.h:37
TestResult
Definition: TestResult.h:26
key
const gtsam::Symbol key('X', 0)
timeOfEvent
static const double timeOfEvent
Definition: testTOAFactor.cpp:43
gtsam
traits
Definition: chartTesting.h:28
TOAFactor.h
"Time of Arrival" factor
K
#define K
Definition: igam.h:8
NonlinearFactorGraph.h
Factor Graph consisting of non-linear factors.
gtsam::Values
Definition: Values.h:65
std
Definition: BFloat16.h:88
gtsam::Values::insert
void insert(Key j, const Value &val)
Definition: Values.cpp:155
gtsam::assert_equal
bool assert_equal(const Matrix &expected, const Matrix &actual, double tol)
Definition: Matrix.cpp:40
ms
static const double ms
Definition: testTOAFactor.cpp:37
gtsam::LevenbergMarquardtParams
Definition: LevenbergMarquardtParams.h:35
gtsam::Point3
Vector3 Point3
Definition: Point3.h:38
graph
NonlinearFactorGraph graph
Definition: doc/Code/OdometryExample.cpp:2
gtsam::Key
std::uint64_t Key
Integer nonlinear key type.
Definition: types.h:97
i
int i
Definition: BiCGSTAB_step_by_step.cpp:9
Event_
Expression< Event > Event_
Definition: testTOAFactor.cpp:34
measurement
static Point2 measurement(323.0, 240.0)
gtsam::FactorGraph::emplace_shared
IsDerived< DERIVEDFACTOR > emplace_shared(Args &&... args)
Emplace a shared pointer to factor of given type.
Definition: FactorGraph.h:153


gtsam
Author(s):
autogenerated on Sat Jun 1 2024 03:07:43