Unit tests for SmartProjectionPoseFactorRollingShutter 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 <gtsam/slam/ProjectionFactor.h>
#include <gtsam_unstable/slam/ProjectionFactorRollingShutter.h>
#include <gtsam_unstable/slam/SmartProjectionPoseFactorRollingShutter.h>
#include <iostream>
#include "gtsam/slam/tests/smartFactorScenarios.h"
#include <gtsam/geometry/SphericalCamera.h>
Go to the source code of this file.
Namespaces | |
sphericalCameraRS | |
vanillaPoseRS | |
Macros | |
#define | DISABLE_TIMING |
Typedefs | |
typedef PinholePose< Cal3_S2 > | vanillaPoseRS::Camera |
typedef SphericalCamera | sphericalCameraRS::Camera |
typedef CameraSet< Camera > | vanillaPoseRS::Cameras |
typedef CameraSet< Camera > | sphericalCameraRS::Cameras |
typedef std::vector< MatrixZD, Eigen::aligned_allocator< MatrixZD > > | FBlocks |
typedef Eigen::Matrix< double, ZDim, DimBlock > | MatrixZD |
typedef SmartProjectionPoseFactorRollingShutter< PinholePose< Cal3_S2 > > | SmartFactorRS |
typedef SmartProjectionPoseFactorRollingShutter< Camera > | sphericalCameraRS::SmartFactorRS_spherical |
Unit tests for SmartProjectionPoseFactorRollingShutter Class.
Definition in file testSmartProjectionPoseFactorRollingShutter.cpp.
#define DISABLE_TIMING |
Definition at line 31 of file testSmartProjectionPoseFactorRollingShutter.cpp.
typedef std::vector<MatrixZD, Eigen::aligned_allocator<MatrixZD> > FBlocks |
Definition at line 222 of file testSmartProjectionPoseFactorRollingShutter.cpp.
typedef Eigen::Matrix<double, ZDim, DimBlock> MatrixZD |
Definition at line 220 of file testSmartProjectionPoseFactorRollingShutter.cpp.
Definition at line 83 of file testSmartProjectionPoseFactorRollingShutter.cpp.
int main | ( | ) |
Definition at line 1485 of file testSmartProjectionPoseFactorRollingShutter.cpp.
|
static |
|
static |
|
static |
|
static |
TEST | ( | SmartProjectionPoseFactorRollingShutter | , |
add | |||
) |
Definition at line 104 of file testSmartProjectionPoseFactorRollingShutter.cpp.
TEST | ( | SmartProjectionPoseFactorRollingShutter | , |
Constructor | |||
) |
Definition at line 86 of file testSmartProjectionPoseFactorRollingShutter.cpp.
TEST | ( | SmartProjectionPoseFactorRollingShutter | , |
Constructor2 | |||
) |
Definition at line 95 of file testSmartProjectionPoseFactorRollingShutter.cpp.
TEST | ( | SmartProjectionPoseFactorRollingShutter | , |
Equals | |||
) |
Definition at line 114 of file testSmartProjectionPoseFactorRollingShutter.cpp.
TEST | ( | SmartProjectionPoseFactorRollingShutter | , |
hessian_simple_2poses | |||
) |
Definition at line 623 of file testSmartProjectionPoseFactorRollingShutter.cpp.
TEST | ( | SmartProjectionPoseFactorRollingShutter | , |
hessianComparedToProjFactorsRollingShutter | |||
) |
Definition at line 942 of file testSmartProjectionPoseFactorRollingShutter.cpp.
TEST | ( | SmartProjectionPoseFactorRollingShutter | , |
hessianComparedToProjFactorsRollingShutter_measurementsFromSamePose | |||
) |
Definition at line 1072 of file testSmartProjectionPoseFactorRollingShutter.cpp.
TEST | ( | SmartProjectionPoseFactorRollingShutter | , |
noiselessErrorAndJacobians | |||
) |
Definition at line 225 of file testSmartProjectionPoseFactorRollingShutter.cpp.
TEST | ( | SmartProjectionPoseFactorRollingShutter | , |
noisyErrorAndJacobians | |||
) |
Definition at line 301 of file testSmartProjectionPoseFactorRollingShutter.cpp.
TEST | ( | SmartProjectionPoseFactorRollingShutter | , |
optimization_3poses | |||
) |
Definition at line 385 of file testSmartProjectionPoseFactorRollingShutter.cpp.
TEST | ( | SmartProjectionPoseFactorRollingShutter | , |
optimization_3poses_dynamicOutlierRejection | |||
) |
Definition at line 855 of file testSmartProjectionPoseFactorRollingShutter.cpp.
TEST | ( | SmartProjectionPoseFactorRollingShutter | , |
optimization_3poses_EPI | |||
) |
Definition at line 719 of file testSmartProjectionPoseFactorRollingShutter.cpp.
TEST | ( | SmartProjectionPoseFactorRollingShutter | , |
optimization_3poses_landmarkDistance | |||
) |
Definition at line 785 of file testSmartProjectionPoseFactorRollingShutter.cpp.
TEST | ( | SmartProjectionPoseFactorRollingShutter | , |
optimization_3poses_measurementsFromSamePose | |||
) |
Definition at line 1227 of file testSmartProjectionPoseFactorRollingShutter.cpp.
TEST | ( | SmartProjectionPoseFactorRollingShutter | , |
optimization_3poses_multiCam | |||
) |
Definition at line 459 of file testSmartProjectionPoseFactorRollingShutter.cpp.
TEST | ( | SmartProjectionPoseFactorRollingShutter | , |
optimization_3poses_multiCam2 | |||
) |
Definition at line 534 of file testSmartProjectionPoseFactorRollingShutter.cpp.
TEST | ( | SmartProjectionPoseFactorRollingShutter | , |
optimization_3poses_sphericalCameras | |||
) |
Definition at line 1402 of file testSmartProjectionPoseFactorRollingShutter.cpp.
|
static |
Definition at line 51 of file testSmartProjectionPoseFactorRollingShutter.cpp.
|
static |
Definition at line 62 of file testSmartProjectionPoseFactorRollingShutter.cpp.
|
static |
size of the variable stacking 2 poses from which the observation pose is interpolated
Definition at line 216 of file testSmartProjectionPoseFactorRollingShutter.cpp.
|
static |
Definition at line 57 of file testSmartProjectionPoseFactorRollingShutter.cpp.
|
static |
Definition at line 58 of file testSmartProjectionPoseFactorRollingShutter.cpp.
|
static |
Definition at line 59 of file testSmartProjectionPoseFactorRollingShutter.cpp.
|
static |
Definition at line 60 of file testSmartProjectionPoseFactorRollingShutter.cpp.
LevenbergMarquardtParams lmParams |
Definition at line 81 of file testSmartProjectionPoseFactorRollingShutter.cpp.
|
static |
Definition at line 36 of file testSmartProjectionPoseFactorRollingShutter.cpp.
|
static |
Definition at line 38 of file testSmartProjectionPoseFactorRollingShutter.cpp.
|
static |
Measurement dimension (Point2)
Definition at line 218 of file testSmartProjectionPoseFactorRollingShutter.cpp.