Unit tests for SmartProjectionRigFactor Class. More...
#include <CppUnitLite/TestHarness.h>
#include <gtsam/base/numericalDerivative.h>
#include <gtsam/base/serializationTestHelpers.h>
#include <gtsam/nonlinear/LevenbergMarquardtOptimizer.h>
#include <gtsam/slam/PoseTranslationPrior.h>
#include <iostream>
#include "smartFactorScenarios.h"
#include <gtsam/slam/ProjectionFactor.h>
Go to the source code of this file.
Namespaces | |
vanillaRig | |
Macros | |
#define | DISABLE_TIMING |
Typedefs | |
typedef GenericProjectionFactor< Pose3, Point3 > | TestProjectionFactor |
Functions | |
int | main () |
static Point2 | measurement1 (323.0, 240.0) |
static SharedIsotropic | model (noiseModel::Isotropic::Sigma(2, sigma)) |
TEST (SmartProjectionFactorP, 2poses_rankTol) | |
TEST (SmartProjectionFactorP, 2poses_sphericalCamera_rankTol) | |
TEST (SmartProjectionFactorP, optimization_3poses_sphericalCamera) | |
TEST (SmartProjectionRigFactor, 3poses_iterative_smart_projection_factor) | |
TEST (SmartProjectionRigFactor, 3poses_smart_projection_factor) | |
TEST (SmartProjectionRigFactor, Cal3Bundler) | |
TEST (SmartProjectionRigFactor, CheckHessian) | |
TEST (SmartProjectionRigFactor, Constructor) | |
TEST (SmartProjectionRigFactor, Constructor2) | |
TEST (SmartProjectionRigFactor, Constructor3) | |
TEST (SmartProjectionRigFactor, Constructor4) | |
TEST (SmartProjectionRigFactor, ConstructorWithCal3Bundler) | |
TEST (SmartProjectionRigFactor, dynamicOutlierRejection) | |
TEST (SmartProjectionRigFactor, Equals) | |
TEST (SmartProjectionRigFactor, Factors) | |
TEST (SmartProjectionRigFactor, Hessian) | |
TEST (SmartProjectionRigFactor, hessianComparedToProjFactors_measurementsFromSamePose) | |
TEST (SmartProjectionRigFactor, landmarkDistance) | |
TEST (SmartProjectionRigFactor, noiseless) | |
TEST (SmartProjectionRigFactor, noisy) | |
TEST (SmartProjectionRigFactor, optimization_3poses_measurementsFromSamePose) | |
TEST (SmartProjectionRigFactor, smartFactorWithMultipleCameras) | |
TEST (SmartProjectionRigFactor, smartFactorWithSensorBodyTransform) | |
Variables | |
Key | cameraId1 = 0 |
Key | cameraId2 = 1 |
Key | cameraId3 = 2 |
static Symbol | l0 ('L', 0) |
LevenbergMarquardtParams | lmParams |
SmartProjectionParams | vanillaRig::params (gtsam::HESSIAN, gtsam::ZERO_ON_DEGENERACY) |
static const double | rankTol = 1.0 |
static const double | sigma = 0.1 |
static Symbol | x1 ('X', 1) |
static Symbol | x2 ('X', 2) |
static Symbol | x3 ('X', 3) |
Unit tests for SmartProjectionRigFactor Class.
Definition in file testSmartProjectionRigFactor.cpp.
#define DISABLE_TIMING |
Definition at line 31 of file testSmartProjectionRigFactor.cpp.
Definition at line 965 of file testSmartProjectionRigFactor.cpp.
int main | ( | ) |
Definition at line 1597 of file testSmartProjectionRigFactor.cpp.
|
static |
|
static |
TEST | ( | SmartProjectionFactorP | , |
2poses_rankTol | |||
) |
Definition at line 1401 of file testSmartProjectionRigFactor.cpp.
TEST | ( | SmartProjectionFactorP | , |
2poses_sphericalCamera_rankTol | |||
) |
Definition at line 1522 of file testSmartProjectionRigFactor.cpp.
TEST | ( | SmartProjectionFactorP | , |
optimization_3poses_sphericalCamera | |||
) |
Definition at line 1248 of file testSmartProjectionRigFactor.cpp.
TEST | ( | SmartProjectionRigFactor | , |
3poses_iterative_smart_projection_factor | |||
) |
Definition at line 565 of file testSmartProjectionRigFactor.cpp.
TEST | ( | SmartProjectionRigFactor | , |
3poses_smart_projection_factor | |||
) |
Definition at line 403 of file testSmartProjectionRigFactor.cpp.
TEST | ( | SmartProjectionRigFactor | , |
Cal3Bundler | |||
) |
Definition at line 899 of file testSmartProjectionRigFactor.cpp.
TEST | ( | SmartProjectionRigFactor | , |
CheckHessian | |||
) |
Definition at line 760 of file testSmartProjectionRigFactor.cpp.
TEST | ( | SmartProjectionRigFactor | , |
Constructor | |||
) |
Definition at line 67 of file testSmartProjectionRigFactor.cpp.
TEST | ( | SmartProjectionRigFactor | , |
Constructor2 | |||
) |
Definition at line 76 of file testSmartProjectionRigFactor.cpp.
TEST | ( | SmartProjectionRigFactor | , |
Constructor3 | |||
) |
Definition at line 87 of file testSmartProjectionRigFactor.cpp.
TEST | ( | SmartProjectionRigFactor | , |
Constructor4 | |||
) |
Definition at line 97 of file testSmartProjectionRigFactor.cpp.
TEST | ( | SmartProjectionRigFactor | , |
ConstructorWithCal3Bundler | |||
) |
Definition at line 887 of file testSmartProjectionRigFactor.cpp.
TEST | ( | SmartProjectionRigFactor | , |
dynamicOutlierRejection | |||
) |
Definition at line 688 of file testSmartProjectionRigFactor.cpp.
TEST | ( | SmartProjectionRigFactor | , |
Equals | |||
) |
Definition at line 110 of file testSmartProjectionRigFactor.cpp.
TEST | ( | SmartProjectionRigFactor | , |
Factors | |||
) |
Definition at line 473 of file testSmartProjectionRigFactor.cpp.
TEST | ( | SmartProjectionRigFactor | , |
Hessian | |||
) |
Definition at line 847 of file testSmartProjectionRigFactor.cpp.
TEST | ( | SmartProjectionRigFactor | , |
hessianComparedToProjFactors_measurementsFromSamePose | |||
) |
Definition at line 968 of file testSmartProjectionRigFactor.cpp.
TEST | ( | SmartProjectionRigFactor | , |
landmarkDistance | |||
) |
Definition at line 625 of file testSmartProjectionRigFactor.cpp.
TEST | ( | SmartProjectionRigFactor | , |
noiseless | |||
) |
Definition at line 133 of file testSmartProjectionRigFactor.cpp.
TEST | ( | SmartProjectionRigFactor | , |
noisy | |||
) |
Definition at line 194 of file testSmartProjectionRigFactor.cpp.
TEST | ( | SmartProjectionRigFactor | , |
optimization_3poses_measurementsFromSamePose | |||
) |
Definition at line 1105 of file testSmartProjectionRigFactor.cpp.
TEST | ( | SmartProjectionRigFactor | , |
smartFactorWithMultipleCameras | |||
) |
Definition at line 316 of file testSmartProjectionRigFactor.cpp.
TEST | ( | SmartProjectionRigFactor | , |
smartFactorWithSensorBodyTransform | |||
) |
Definition at line 235 of file testSmartProjectionRigFactor.cpp.
Key cameraId1 = 0 |
Definition at line 49 of file testSmartProjectionRigFactor.cpp.
Key cameraId2 = 1 |
Definition at line 50 of file testSmartProjectionRigFactor.cpp.
Key cameraId3 = 2 |
Definition at line 51 of file testSmartProjectionRigFactor.cpp.
LevenbergMarquardtParams lmParams |
Definition at line 55 of file testSmartProjectionRigFactor.cpp.
|
static |
Definition at line 35 of file testSmartProjectionRigFactor.cpp.
|
static |
Definition at line 37 of file testSmartProjectionRigFactor.cpp.