Unit tests for ProjectionFactor Class. More...
#include "smartFactorScenarios.h"#include <gtsam/slam/ProjectionFactor.h>#include <gtsam/slam/PoseTranslationPrior.h>#include <gtsam/nonlinear/LevenbergMarquardtOptimizer.h>#include <gtsam/base/numericalDerivative.h>#include <gtsam/base/serializationTestHelpers.h>#include <CppUnitLite/TestHarness.h>#include <boost/assign/std/map.hpp>#include <iostream>
Go to the source code of this file.
Variables | |
| LevenbergMarquardtParams | lmParams |
| 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 ProjectionFactor Class.
Definition in file testSmartProjectionPoseFactor.cpp.
| BOOST_CLASS_EXPORT_GUID | ( | gtsam::noiseModel::Constrained | , |
| "gtsam_noiseModel_Constrained" | |||
| ) |
| BOOST_CLASS_EXPORT_GUID | ( | gtsam::noiseModel::Diagonal | , |
| "gtsam_noiseModel_Diagonal" | |||
| ) |
| BOOST_CLASS_EXPORT_GUID | ( | gtsam::noiseModel::Gaussian | , |
| "gtsam_noiseModel_Gaussian" | |||
| ) |
| BOOST_CLASS_EXPORT_GUID | ( | gtsam::noiseModel::Unit | , |
| "gtsam_noiseModel_Unit" | |||
| ) |
| BOOST_CLASS_EXPORT_GUID | ( | gtsam::noiseModel::Isotropic | , |
| "gtsam_noiseModel_Isotropic" | |||
| ) |
| BOOST_CLASS_EXPORT_GUID | ( | gtsam::SharedNoiseModel | , |
| "gtsam_SharedNoiseModel" | |||
| ) |
| BOOST_CLASS_EXPORT_GUID | ( | gtsam::SharedDiagonal | , |
| "gtsam_SharedDiagonal" | |||
| ) |
| int main | ( | void | ) |
Definition at line 1376 of file testSmartProjectionPoseFactor.cpp.
|
static |
|
static |
| TEST | ( | SmartProjectionPoseFactor | , |
| Constructor | |||
| ) |
Definition at line 55 of file testSmartProjectionPoseFactor.cpp.
| TEST | ( | SmartProjectionPoseFactor | , |
| Constructor2 | |||
| ) |
Definition at line 61 of file testSmartProjectionPoseFactor.cpp.
| TEST | ( | SmartProjectionPoseFactor | , |
| Constructor3 | |||
| ) |
Definition at line 69 of file testSmartProjectionPoseFactor.cpp.
| TEST | ( | SmartProjectionPoseFactor | , |
| Constructor4 | |||
| ) |
Definition at line 76 of file testSmartProjectionPoseFactor.cpp.
| TEST | ( | SmartProjectionPoseFactor | , |
| params | |||
| ) |
Definition at line 85 of file testSmartProjectionPoseFactor.cpp.
| TEST | ( | SmartProjectionPoseFactor | , |
| Equals | |||
| ) |
Definition at line 96 of file testSmartProjectionPoseFactor.cpp.
| TEST | ( | SmartProjectionPoseFactor | , |
| noiseless | |||
| ) |
Definition at line 108 of file testSmartProjectionPoseFactor.cpp.
| TEST | ( | SmartProjectionPoseFactor | , |
| noisy | |||
| ) |
Definition at line 166 of file testSmartProjectionPoseFactor.cpp.
| TEST | ( | SmartProjectionPoseFactor | , |
| smartFactorWithSensorBodyTransform | |||
| ) |
Definition at line 200 of file testSmartProjectionPoseFactor.cpp.
| TEST | ( | SmartProjectionPoseFactor | , |
| 3poses_smart_projection_factor | |||
| ) |
Definition at line 275 of file testSmartProjectionPoseFactor.cpp.
| TEST | ( | SmartProjectionPoseFactor | , |
| Factors | |||
| ) |
Definition at line 336 of file testSmartProjectionPoseFactor.cpp.
| TEST | ( | SmartProjectionPoseFactor | , |
| 3poses_iterative_smart_projection_factor | |||
| ) |
Definition at line 500 of file testSmartProjectionPoseFactor.cpp.
| TEST | ( | SmartProjectionPoseFactor | , |
| jacobianSVD | |||
| ) |
Definition at line 554 of file testSmartProjectionPoseFactor.cpp.
| TEST | ( | SmartProjectionPoseFactor | , |
| landmarkDistance | |||
| ) |
Definition at line 610 of file testSmartProjectionPoseFactor.cpp.
| TEST | ( | SmartProjectionPoseFactor | , |
| dynamicOutlierRejection | |||
| ) |
Definition at line 669 of file testSmartProjectionPoseFactor.cpp.
| TEST | ( | SmartProjectionPoseFactor | , |
| jacobianQ | |||
| ) |
Definition at line 735 of file testSmartProjectionPoseFactor.cpp.
| TEST | ( | SmartProjectionPoseFactor | , |
| 3poses_projection_factor | |||
| ) |
Definition at line 786 of file testSmartProjectionPoseFactor.cpp.
| TEST | ( | SmartProjectionPoseFactor | , |
| CheckHessian | |||
| ) |
Definition at line 833 of file testSmartProjectionPoseFactor.cpp.
| TEST | ( | SmartProjectionPoseFactor | , |
| 3poses_2land_rotation_only_smart_projection_factor | |||
| ) |
Definition at line 915 of file testSmartProjectionPoseFactor.cpp.
| TEST | ( | SmartProjectionPoseFactor | , |
| 3poses_rotation_only_smart_projection_factor | |||
| ) |
Definition at line 969 of file testSmartProjectionPoseFactor.cpp.
| TEST | ( | SmartProjectionPoseFactor | , |
| Hessian | |||
| ) |
Definition at line 1052 of file testSmartProjectionPoseFactor.cpp.
| TEST | ( | SmartProjectionPoseFactor | , |
| HessianWithRotation | |||
| ) |
Definition at line 1083 of file testSmartProjectionPoseFactor.cpp.
| TEST | ( | SmartProjectionPoseFactor | , |
| HessianWithRotationDegenerate | |||
| ) |
Definition at line 1134 of file testSmartProjectionPoseFactor.cpp.
| TEST | ( | SmartProjectionPoseFactor | , |
| ConstructorWithCal3Bundler | |||
| ) |
Definition at line 1186 of file testSmartProjectionPoseFactor.cpp.
| TEST | ( | SmartProjectionPoseFactor | , |
| Cal3Bundler | |||
| ) |
Definition at line 1195 of file testSmartProjectionPoseFactor.cpp.
| TEST | ( | SmartProjectionPoseFactor | , |
| Cal3BundlerRotationOnly | |||
| ) |
Definition at line 1251 of file testSmartProjectionPoseFactor.cpp.
| TEST | ( | SmartProjectionPoseFactor | , |
| serialize | |||
| ) |
Definition at line 1343 of file testSmartProjectionPoseFactor.cpp.
| TEST | ( | SmartProjectionPoseFactor | , |
| serialize2 | |||
| ) |
Definition at line 1355 of file testSmartProjectionPoseFactor.cpp.
| LevenbergMarquardtParams lmParams |
Definition at line 50 of file testSmartProjectionPoseFactor.cpp.
|
static |
Definition at line 34 of file testSmartProjectionPoseFactor.cpp.
|
static |
Definition at line 36 of file testSmartProjectionPoseFactor.cpp.