#include <gtsam/slam/tests/smartFactorScenarios.h>#include <gtsam_unstable/slam/SmartStereoProjectionPoseFactor.h>#include <gtsam/nonlinear/LevenbergMarquardtOptimizer.h>#include <gtsam/slam/PoseTranslationPrior.h>#include <gtsam/slam/ProjectionFactor.h>#include <gtsam/slam/StereoFactor.h>#include <boost/assign/std/vector.hpp>#include <CppUnitLite/TestHarness.h>#include <iostream>
Go to the source code of this file.
Variables | |
| static double | b = 1 |
| static Pose3 | body_P_sensor1 (Rot3::RzRyRx(-M_PI_2, 0.0,-M_PI_2), Point3(0.25,-0.10, 1.0)) |
| LevenbergMarquardtParams | lm_params |
| static StereoPoint2 | measurement1 (323.0, 300.0, 240.0) |
| static double | missing_uR = std::numeric_limits<double>::quiet_NaN() |
| static SmartStereoProjectionParams | params |
| static Symbol | x1 ('X', 1) |
| static Symbol | x2 ('X', 2) |
| static Symbol | x3 ('X', 3) |
|
static |
|
static |
| int main | ( | void | ) |
Definition at line 1456 of file testSmartStereoProjectionPoseFactor.cpp.
|
static |
| vector<StereoPoint2> stereo_projectToMultipleCameras | ( | const StereoCamera & | cam1, |
| const StereoCamera & | cam2, | ||
| const StereoCamera & | cam3, | ||
| Point3 | landmark | ||
| ) |
Definition at line 65 of file testSmartStereoProjectionPoseFactor.cpp.
| TEST | ( | SmartStereoProjectionPoseFactor | , |
| params | |||
| ) |
Definition at line 83 of file testSmartStereoProjectionPoseFactor.cpp.
| TEST | ( | SmartStereoProjectionPoseFactor | , |
| Constructor | |||
| ) |
Definition at line 112 of file testSmartStereoProjectionPoseFactor.cpp.
| TEST | ( | SmartStereoProjectionPoseFactor | , |
| Constructor2 | |||
| ) |
Definition at line 117 of file testSmartStereoProjectionPoseFactor.cpp.
| TEST | ( | SmartStereoProjectionPoseFactor | , |
| Constructor3 | |||
| ) |
Definition at line 122 of file testSmartStereoProjectionPoseFactor.cpp.
| TEST | ( | SmartStereoProjectionPoseFactor | , |
| Constructor4 | |||
| ) |
Definition at line 128 of file testSmartStereoProjectionPoseFactor.cpp.
| TEST | ( | SmartStereoProjectionPoseFactor | , |
| Equals | |||
| ) |
Definition at line 134 of file testSmartStereoProjectionPoseFactor.cpp.
| TEST | ( | SmartProjectionPoseFactor | , |
| noiselessWithMissingMeasurements | |||
| ) |
Definition at line 184 of file testSmartStereoProjectionPoseFactor.cpp.
| TEST | ( | SmartStereoProjectionPoseFactor | , |
| noisy | |||
| ) |
< shared pointer to calibration object (one for each camera)
Definition at line 238 of file testSmartStereoProjectionPoseFactor.cpp.
| TEST | ( | SmartStereoProjectionPoseFactor | , |
| 3poses_smart_projection_factor | |||
| ) |
Definition at line 289 of file testSmartStereoProjectionPoseFactor.cpp.
| TEST | ( | SmartStereoProjectionPoseFactor | , |
| body_P_sensor | |||
| ) |
Definition at line 429 of file testSmartStereoProjectionPoseFactor.cpp.
| TEST | ( | SmartStereoProjectionPoseFactor | , |
| body_P_sensor_monocular | |||
| ) |
Definition at line 514 of file testSmartStereoProjectionPoseFactor.cpp.
| TEST | ( | SmartStereoProjectionPoseFactor | , |
| jacobianSVD | |||
| ) |
Definition at line 615 of file testSmartStereoProjectionPoseFactor.cpp.
| TEST | ( | SmartStereoProjectionPoseFactor | , |
| jacobianSVDwithMissingValues | |||
| ) |
Definition at line 681 of file testSmartStereoProjectionPoseFactor.cpp.
| TEST | ( | SmartStereoProjectionPoseFactor | , |
| landmarkDistance | |||
| ) |
Definition at line 753 of file testSmartStereoProjectionPoseFactor.cpp.
| TEST | ( | SmartStereoProjectionPoseFactor | , |
| dynamicOutlierRejection | |||
| ) |
Definition at line 823 of file testSmartStereoProjectionPoseFactor.cpp.
| TEST | ( | SmartStereoProjectionPoseFactor | , |
| CheckHessian | |||
| ) |
Definition at line 1041 of file testSmartStereoProjectionPoseFactor.cpp.
| TEST | ( | SmartStereoProjectionPoseFactor | , |
| HessianWithRotation | |||
| ) |
Definition at line 1311 of file testSmartStereoProjectionPoseFactor.cpp.
| TEST | ( | SmartStereoProjectionPoseFactor | , |
| HessianWithRotationNonDegenerate | |||
| ) |
Definition at line 1380 of file testSmartStereoProjectionPoseFactor.cpp.
| TEST_UNSAFE | ( | SmartStereoProjectionPoseFactor | , |
| noiseless | |||
| ) |
Definition at line 145 of file testSmartStereoProjectionPoseFactor.cpp.
|
static |
Definition at line 36 of file testSmartStereoProjectionPoseFactor.cpp.
| LevenbergMarquardtParams lm_params |
Definition at line 80 of file testSmartStereoProjectionPoseFactor.cpp.
|
static |
|
static |
Definition at line 63 of file testSmartStereoProjectionPoseFactor.cpp.
|
static |
Definition at line 43 of file testSmartStereoProjectionPoseFactor.cpp.