Unit tests for "Time of Arrival" factor. More...
#include <gtsam/base/numericalDerivative.h>#include <gtsam/nonlinear/LevenbergMarquardtOptimizer.h>#include <gtsam/nonlinear/NonlinearFactorGraph.h>#include <gtsam/nonlinear/expressions.h>#include <gtsam/geometry/Event.h>#include <gtsam_unstable/slam/TOAFactor.h>#include <CppUnitLite/TestHarness.h>
Go to the source code of this file.
Typedefs | |
| typedef Expression< Event > | Event_ |
| typedef Expression< Point3 > | Point3_ |
Functions | |
| int | main () |
| static SharedNoiseModel | model (noiseModel::Isotropic::Sigma(1, 0.5 *ms)) |
| static const Point3 | sensorAt0 (0, 0, 0) |
| TEST (TOAFactor, NewWay) | |
| TEST (TOAFactor, WholeEnchilada) | |
Variables | |
| static const double | cm = 1e-2 |
| static const Event | exampleEvent (timeOfEvent, 1, 0, 0) |
| static const double | ms = 1e-3 |
| static const double | timeOfEvent = 25 |
| typedef Expression<Event> Event_ |
Definition at line 34 of file testTOAFactor.cpp.
| typedef Expression<Point3> Point3_ |
Definition at line 33 of file testTOAFactor.cpp.
| int main | ( | ) |
Definition at line 102 of file testTOAFactor.cpp.
|
static |
|
static |
| TEST | ( | TOAFactor | , |
| NewWay | |||
| ) |
Definition at line 48 of file testTOAFactor.cpp.
| TEST | ( | TOAFactor | , |
| WholeEnchilada | |||
| ) |
Definition at line 55 of file testTOAFactor.cpp.
|
static |
Definition at line 38 of file testTOAFactor.cpp.
|
static |
|
static |
Definition at line 37 of file testTOAFactor.cpp.
|
static |
Definition at line 43 of file testTOAFactor.cpp.