Public Member Functions | Static Public Member Functions | Public Attributes | List of all members
gtsam::Switching Struct Reference

ϕ(X(0)) .. ϕ(X(k),X(k+1)) .. ϕ(X(k);z_k) .. ϕ(M(0)) .. ϕ(M(K-3),M(K-2)) More...

#include <Switching.h>

Public Member Functions

HybridNonlinearFactorGraph createModeChain (std::string transitionProbabilityTable="1/2 3/2")
 Add "mode chain" to HybridNonlinearFactorGraph from M(0) to M(K-2). E.g. if K=4, we want M0, M1 and M2. More...
 
HybridGaussianFactorGraph linearizedFactorGraph () const
 Get the full linear factor graph. More...
 
HybridNonlinearFactorGraph nonlinearFactorGraph () const
 Get all the nonlinear factors. More...
 
 Switching (size_t K, double between_sigma=1.0, double prior_sigma=0.1, std::vector< double > measurements={}, std::string transitionProbabilityTable="1/2 3/2")
 Create with given number of time steps. More...
 

Static Public Member Functions

static std::vector< NoiseModelFactor::shared_ptrmotionModels (size_t k, double sigma=1.0)
 

Public Attributes

HybridNonlinearFactorGraph binaryFactors
 
size_t K
 
HybridGaussianFactorGraph linearBinaryFactors
 
Values linearizationPoint
 
HybridGaussianFactorGraph linearUnaryFactors
 
HybridNonlinearFactorGraph modeChain
 
DiscreteKeys modes
 
HybridNonlinearFactorGraph unaryFactors
 

Detailed Description

ϕ(X(0)) .. ϕ(X(k),X(k+1)) .. ϕ(X(k);z_k) .. ϕ(M(0)) .. ϕ(M(K-3),M(K-2))

Definition at line 124 of file Switching.h.

Constructor & Destructor Documentation

◆ Switching()

gtsam::Switching::Switching ( size_t  K,
double  between_sigma = 1.0,
double  prior_sigma = 0.1,
std::vector< double >  measurements = {},
std::string  transitionProbabilityTable = "1/2 3/2" 
)
inline

Create with given number of time steps.

Parameters
KThe total number of timesteps.
between_sigmaThe stddev between poses.
prior_sigmaThe stddev on priors (also used for measurements).
measurementsVector of measurements for each timestep.

Definition at line 140 of file Switching.h.

Member Function Documentation

◆ createModeChain()

HybridNonlinearFactorGraph gtsam::Switching::createModeChain ( std::string  transitionProbabilityTable = "1/2 3/2")
inline

Add "mode chain" to HybridNonlinearFactorGraph from M(0) to M(K-2). E.g. if K=4, we want M0, M1 and M2.

Parameters
fgThe factor graph to which the mode chain is added.

Definition at line 207 of file Switching.h.

◆ linearizedFactorGraph()

HybridGaussianFactorGraph gtsam::Switching::linearizedFactorGraph ( ) const
inline

Get the full linear factor graph.

Definition at line 220 of file Switching.h.

◆ motionModels()

static std::vector<NoiseModelFactor::shared_ptr> gtsam::Switching::motionModels ( size_t  k,
double  sigma = 1.0 
)
inlinestatic

Definition at line 191 of file Switching.h.

◆ nonlinearFactorGraph()

HybridNonlinearFactorGraph gtsam::Switching::nonlinearFactorGraph ( ) const
inline

Get all the nonlinear factors.

Definition at line 229 of file Switching.h.

Member Data Documentation

◆ binaryFactors

HybridNonlinearFactorGraph gtsam::Switching::binaryFactors

Definition at line 128 of file Switching.h.

◆ K

size_t gtsam::Switching::K

Definition at line 126 of file Switching.h.

◆ linearBinaryFactors

HybridGaussianFactorGraph gtsam::Switching::linearBinaryFactors

Definition at line 129 of file Switching.h.

◆ linearizationPoint

Values gtsam::Switching::linearizationPoint

Definition at line 130 of file Switching.h.

◆ linearUnaryFactors

HybridGaussianFactorGraph gtsam::Switching::linearUnaryFactors

Definition at line 129 of file Switching.h.

◆ modeChain

HybridNonlinearFactorGraph gtsam::Switching::modeChain

Definition at line 128 of file Switching.h.

◆ modes

DiscreteKeys gtsam::Switching::modes

Definition at line 127 of file Switching.h.

◆ unaryFactors

HybridNonlinearFactorGraph gtsam::Switching::unaryFactors

Definition at line 128 of file Switching.h.


The documentation for this struct was generated from the following file:


gtsam
Author(s):
autogenerated on Sat Nov 16 2024 04:16:31