Public Member Functions | Public Attributes | Private Member Functions | Private Attributes | List of all members
Experiment Class Reference

Public Member Functions

 Experiment (const std::string &filename)
 Construct with filename of experiment to run. More...
 
 Experiment (const std::string &filename, bool isWithAmbiguity=false)
 Construct with filename of experiment to run. More...
 
void run ()
 Run the main experiment with a given maxLoopCount. More...
 
void run ()
 Run the main experiment with a given maxLoopCount. More...
 

Public Attributes

bool isWithAmbiguity
 
double marginalThreshold = 0.9999
 
size_t maxLoopCount = 8000
 
size_t maxNrHypotheses = 10
 
size_t reLinearizationFrequency = 10
 
size_t updateFrequency = 3
 

Private Member Functions

HybridNonlinearFactor hybridLoopClosureFactor (size_t loopCounter, size_t keyS, size_t keyT, const Pose2 &measurement) const
 Create a hybrid loop closure factor where 0 - loose noise model and 1 - loop noise model. More...
 
HybridNonlinearFactor hybridOdometryFactor (size_t numMeasurements, size_t keyS, size_t keyT, const DiscreteKey &m, const std::vector< Pose2 > &poseArray) const
 Create hybrid odometry factor with discrete measurement choices. More...
 
clock_t reInitialize ()
 Re-linearize, solve ALL, and re-initialize smoother. More...
 
clock_t smootherUpdate (size_t maxNrHypotheses)
 Perform smoother update and optimize the graph. More...
 

Private Attributes

HybridNonlinearFactorGraph allFactors_
 
City10000Dataset dataset_
 The City10000 dataset. More...
 
NonlinearFactorGraph graph_
 
Values initial_
 
ISAM2 isam2_
 
HybridNonlinearFactorGraph newFactors_
 
Values results
 
HybridSmoother smoother_
 

Detailed Description

Definition at line 47 of file Hybrid_City10000.cpp.

Constructor & Destructor Documentation

◆ Experiment() [1/2]

Experiment::Experiment ( const std::string &  filename)
inlineexplicit

Construct with filename of experiment to run.

Definition at line 139 of file Hybrid_City10000.cpp.

◆ Experiment() [2/2]

Experiment::Experiment ( const std::string &  filename,
bool  isWithAmbiguity = false 
)
inlineexplicit

Construct with filename of experiment to run.

Definition at line 63 of file ISAM2_City10000.cpp.

Member Function Documentation

◆ hybridLoopClosureFactor()

HybridNonlinearFactor Experiment::hybridLoopClosureFactor ( size_t  loopCounter,
size_t  keyS,
size_t  keyT,
const Pose2 measurement 
) const
inlineprivate

Create a hybrid loop closure factor where 0 - loose noise model and 1 - loop noise model.

Definition at line 76 of file Hybrid_City10000.cpp.

◆ hybridOdometryFactor()

HybridNonlinearFactor Experiment::hybridOdometryFactor ( size_t  numMeasurements,
size_t  keyS,
size_t  keyT,
const DiscreteKey m,
const std::vector< Pose2 > &  poseArray 
) const
inlineprivate

Create hybrid odometry factor with discrete measurement choices.

Definition at line 93 of file Hybrid_City10000.cpp.

◆ reInitialize()

clock_t Experiment::reInitialize ( )
inlineprivate

Re-linearize, solve ALL, and re-initialize smoother.

Definition at line 121 of file Hybrid_City10000.cpp.

◆ run() [1/2]

void Experiment::run ( )
inline

Run the main experiment with a given maxLoopCount.

Write results to file

Definition at line 73 of file ISAM2_City10000.cpp.

◆ run() [2/2]

void Experiment::run ( )
inline

Run the main experiment with a given maxLoopCount.

Definition at line 143 of file Hybrid_City10000.cpp.

◆ smootherUpdate()

clock_t Experiment::smootherUpdate ( size_t  maxNrHypotheses)
inlineprivate

Perform smoother update and optimize the graph.

Definition at line 108 of file Hybrid_City10000.cpp.

Member Data Documentation

◆ allFactors_

HybridNonlinearFactorGraph Experiment::allFactors_
private

Definition at line 69 of file Hybrid_City10000.cpp.

◆ dataset_

City10000Dataset Experiment::dataset_
private

The City10000 dataset.

Definition at line 49 of file Hybrid_City10000.cpp.

◆ graph_

NonlinearFactorGraph Experiment::graph_
private

Definition at line 57 of file ISAM2_City10000.cpp.

◆ initial_

Values Experiment::initial_
private

Definition at line 70 of file Hybrid_City10000.cpp.

◆ isam2_

ISAM2 Experiment::isam2_
private

Definition at line 56 of file ISAM2_City10000.cpp.

◆ isWithAmbiguity

bool Experiment::isWithAmbiguity

Definition at line 53 of file ISAM2_City10000.cpp.

◆ marginalThreshold

double Experiment::marginalThreshold = 0.9999

Definition at line 65 of file Hybrid_City10000.cpp.

◆ maxLoopCount

size_t Experiment::maxLoopCount = 8000

Definition at line 53 of file Hybrid_City10000.cpp.

◆ maxNrHypotheses

size_t Experiment::maxNrHypotheses = 10

Definition at line 61 of file Hybrid_City10000.cpp.

◆ newFactors_

HybridNonlinearFactorGraph Experiment::newFactors_
private

Definition at line 69 of file Hybrid_City10000.cpp.

◆ reLinearizationFrequency

size_t Experiment::reLinearizationFrequency = 10

Definition at line 63 of file Hybrid_City10000.cpp.

◆ results

Values Experiment::results
private

Definition at line 59 of file ISAM2_City10000.cpp.

◆ smoother_

HybridSmoother Experiment::smoother_
private

Definition at line 68 of file Hybrid_City10000.cpp.

◆ updateFrequency

size_t Experiment::updateFrequency = 3

Definition at line 59 of file Hybrid_City10000.cpp.


The documentation for this class was generated from the following files:


gtsam
Author(s):
autogenerated on Fri Mar 28 2025 03:09:33