Namespaces | Macros | Typedefs | Functions | Variables
testSmartProjectionRigFactor.cpp File Reference

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>
Include dependency graph for testSmartProjectionRigFactor.cpp:

Go to the source code of this file.

Namespaces

 vanillaRig
 

Macros

#define DISABLE_TIMING
 

Typedefs

typedef GenericProjectionFactor< Pose3, Point3TestProjectionFactor
 

Functions

int main ()
 
static Point2 measurement1 (323.0, 240.0)
 
static SharedIsotropic model (noiseModel::Isotropic::Sigma(2, sigma))
 
 TEST (SmartProjectionRigFactor, Constructor)
 
 TEST (SmartProjectionRigFactor, Constructor2)
 
 TEST (SmartProjectionRigFactor, Constructor3)
 
 TEST (SmartProjectionRigFactor, Constructor4)
 
 TEST (SmartProjectionRigFactor, Equals)
 
 TEST (SmartProjectionRigFactor, noiseless)
 
 TEST (SmartProjectionRigFactor, noisy)
 
 TEST (SmartProjectionRigFactor, smartFactorWithSensorBodyTransform)
 
 TEST (SmartProjectionRigFactor, smartFactorWithMultipleCameras)
 
 TEST (SmartProjectionRigFactor, 3poses_smart_projection_factor)
 
 TEST (SmartProjectionRigFactor, Factors)
 
 TEST (SmartProjectionRigFactor, 3poses_iterative_smart_projection_factor)
 
 TEST (SmartProjectionRigFactor, landmarkDistance)
 
 TEST (SmartProjectionRigFactor, dynamicOutlierRejection)
 
 TEST (SmartProjectionRigFactor, CheckHessian)
 
 TEST (SmartProjectionRigFactor, Hessian)
 
 TEST (SmartProjectionRigFactor, ConstructorWithCal3Bundler)
 
 TEST (SmartProjectionRigFactor, Cal3Bundler)
 
 TEST (SmartProjectionRigFactor, hessianComparedToProjFactors_measurementsFromSamePose)
 
 TEST (SmartProjectionRigFactor, optimization_3poses_measurementsFromSamePose)
 
 TEST (SmartProjectionFactorP, optimization_3poses_sphericalCamera)
 
 TEST (SmartProjectionFactorP, 2poses_rankTol)
 
 TEST (SmartProjectionFactorP, 2poses_sphericalCamera_rankTol)
 

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)
 

Detailed Description

Unit tests for SmartProjectionRigFactor Class.

Author
Chris Beall
Luca Carlone
Zsolt Kira
Frank Dellaert
Date
August 2021

Definition in file testSmartProjectionRigFactor.cpp.

Macro Definition Documentation

◆ DISABLE_TIMING

#define DISABLE_TIMING

Definition at line 31 of file testSmartProjectionRigFactor.cpp.

Typedef Documentation

◆ TestProjectionFactor

Definition at line 965 of file testSmartProjectionRigFactor.cpp.

Function Documentation

◆ main()

int main ( void  )

Definition at line 1597 of file testSmartProjectionRigFactor.cpp.

◆ measurement1()

static Point2 measurement1 ( 323.  0,
240.  0 
)
static

◆ model()

static SharedIsotropic model ( noiseModel::Isotropic::Sigma(2, sigma )
static

◆ TEST() [1/23]

TEST ( SmartProjectionRigFactor  ,
Constructor   
)

Definition at line 67 of file testSmartProjectionRigFactor.cpp.

◆ TEST() [2/23]

TEST ( SmartProjectionRigFactor  ,
Constructor2   
)

Definition at line 76 of file testSmartProjectionRigFactor.cpp.

◆ TEST() [3/23]

TEST ( SmartProjectionRigFactor  ,
Constructor3   
)

Definition at line 87 of file testSmartProjectionRigFactor.cpp.

◆ TEST() [4/23]

TEST ( SmartProjectionRigFactor  ,
Constructor4   
)

Definition at line 97 of file testSmartProjectionRigFactor.cpp.

◆ TEST() [5/23]

TEST ( SmartProjectionRigFactor  ,
Equals   
)

Definition at line 110 of file testSmartProjectionRigFactor.cpp.

◆ TEST() [6/23]

TEST ( SmartProjectionRigFactor  ,
noiseless   
)

Definition at line 133 of file testSmartProjectionRigFactor.cpp.

◆ TEST() [7/23]

TEST ( SmartProjectionRigFactor  ,
noisy   
)

Definition at line 194 of file testSmartProjectionRigFactor.cpp.

◆ TEST() [8/23]

TEST ( SmartProjectionRigFactor  ,
smartFactorWithSensorBodyTransform   
)

Definition at line 235 of file testSmartProjectionRigFactor.cpp.

◆ TEST() [9/23]

TEST ( SmartProjectionRigFactor  ,
smartFactorWithMultipleCameras   
)

Definition at line 316 of file testSmartProjectionRigFactor.cpp.

◆ TEST() [10/23]

TEST ( SmartProjectionRigFactor  ,
3poses_smart_projection_factor   
)

Definition at line 403 of file testSmartProjectionRigFactor.cpp.

◆ TEST() [11/23]

TEST ( SmartProjectionRigFactor  ,
Factors   
)

Definition at line 473 of file testSmartProjectionRigFactor.cpp.

◆ TEST() [12/23]

TEST ( SmartProjectionRigFactor  ,
3poses_iterative_smart_projection_factor   
)

Definition at line 565 of file testSmartProjectionRigFactor.cpp.

◆ TEST() [13/23]

TEST ( SmartProjectionRigFactor  ,
landmarkDistance   
)

Definition at line 625 of file testSmartProjectionRigFactor.cpp.

◆ TEST() [14/23]

TEST ( SmartProjectionRigFactor  ,
dynamicOutlierRejection   
)

Definition at line 688 of file testSmartProjectionRigFactor.cpp.

◆ TEST() [15/23]

TEST ( SmartProjectionRigFactor  ,
CheckHessian   
)

Definition at line 760 of file testSmartProjectionRigFactor.cpp.

◆ TEST() [16/23]

TEST ( SmartProjectionRigFactor  ,
Hessian   
)

Definition at line 847 of file testSmartProjectionRigFactor.cpp.

◆ TEST() [17/23]

TEST ( SmartProjectionRigFactor  ,
ConstructorWithCal3Bundler   
)

Definition at line 887 of file testSmartProjectionRigFactor.cpp.

◆ TEST() [18/23]

Definition at line 899 of file testSmartProjectionRigFactor.cpp.

◆ TEST() [19/23]

TEST ( SmartProjectionRigFactor  ,
hessianComparedToProjFactors_measurementsFromSamePose   
)

Definition at line 968 of file testSmartProjectionRigFactor.cpp.

◆ TEST() [20/23]

TEST ( SmartProjectionRigFactor  ,
optimization_3poses_measurementsFromSamePose   
)

Definition at line 1105 of file testSmartProjectionRigFactor.cpp.

◆ TEST() [21/23]

TEST ( SmartProjectionFactorP  ,
optimization_3poses_sphericalCamera   
)

Definition at line 1248 of file testSmartProjectionRigFactor.cpp.

◆ TEST() [22/23]

TEST ( SmartProjectionFactorP  ,
2poses_rankTol   
)

Definition at line 1401 of file testSmartProjectionRigFactor.cpp.

◆ TEST() [23/23]

TEST ( SmartProjectionFactorP  ,
2poses_sphericalCamera_rankTol   
)

Definition at line 1522 of file testSmartProjectionRigFactor.cpp.

Variable Documentation

◆ cameraId1

Key cameraId1 = 0

Definition at line 49 of file testSmartProjectionRigFactor.cpp.

◆ cameraId2

Key cameraId2 = 1

Definition at line 50 of file testSmartProjectionRigFactor.cpp.

◆ cameraId3

Key cameraId3 = 2

Definition at line 51 of file testSmartProjectionRigFactor.cpp.

◆ l0

Symbol l0( 'L', 0)
static

◆ lmParams

Definition at line 55 of file testSmartProjectionRigFactor.cpp.

◆ rankTol

const double rankTol = 1.0
static

Definition at line 35 of file testSmartProjectionRigFactor.cpp.

◆ sigma

const double sigma = 0.1
static

Definition at line 37 of file testSmartProjectionRigFactor.cpp.

◆ x1

Symbol x1( 'X', 1)
static

◆ x2

Symbol x2( 'X', 2)
static

◆ x3

Symbol x3( 'X', 3)
static


gtsam
Author(s):
autogenerated on Tue Jul 4 2023 02:40:56