dcsam
Factored inference for discrete-continuous smoothing and mapping
dcsam::DCContinuousFactor Class Reference

Implementation of a discrete-continuous factor. This is used internally within the DCSAM solver. Essentially this class wraps a DCFactor (given as argument) into a continuous factor (gtsam::NonlinearFactor) that can be passed to GTSAM/iSAM/iSAM2 for continuous optimization with a fixed assignment to discrete variables. More...

#include <DCContinuousFactor.h>

Inheritance diagram for dcsam::DCContinuousFactor:
Collaboration diagram for dcsam::DCContinuousFactor:

Public Types

using Base = gtsam::NonlinearFactor
 

Public Member Functions

 DCContinuousFactor ()=default
 
 DCContinuousFactor (boost::shared_ptr< DCFactor > dcfactor)
 
double error (const gtsam::Values &continuousVals) const override
 
boost::shared_ptr< gtsam::GaussianFactor > linearize (const gtsam::Values &continuousVals) const override
 
DCContinuousFactoroperator= (const DCContinuousFactor &rhs)
 
 ~DCContinuousFactor ()=default
 
bool updateDiscrete (const DiscreteValues &discreteVals)
 
size_t dim () const override
 
bool allInitialized () const
 

Detailed Description

Implementation of a discrete-continuous factor. This is used internally within the DCSAM solver. Essentially this class wraps a DCFactor (given as argument) into a continuous factor (gtsam::NonlinearFactor) that can be passed to GTSAM/iSAM/iSAM2 for continuous optimization with a fixed assignment to discrete variables.

After running an iteration of continuous optimization (and separately, discrete optimization), the updateDiscrete function is used to ensure the stored discrete value assignment matches the most recent estimate for discrete variables.

The discrete analogue is DCDiscreteFactor.

Member Typedef Documentation

◆ Base

using dcsam::DCContinuousFactor::Base = gtsam::NonlinearFactor

Constructor & Destructor Documentation

◆ DCContinuousFactor() [1/2]

dcsam::DCContinuousFactor::DCContinuousFactor ( )
default

◆ DCContinuousFactor() [2/2]

dcsam::DCContinuousFactor::DCContinuousFactor ( boost::shared_ptr< DCFactor dcfactor)
inlineexplicit

◆ ~DCContinuousFactor()

dcsam::DCContinuousFactor::~DCContinuousFactor ( )
default

Member Function Documentation

◆ allInitialized()

bool dcsam::DCContinuousFactor::allInitialized ( ) const
inline

◆ dim()

size_t dcsam::DCContinuousFactor::dim ( ) const
inlineoverride

◆ error()

double dcsam::DCContinuousFactor::error ( const gtsam::Values &  continuousVals) const
inlineoverride

◆ linearize()

boost::shared_ptr<gtsam::GaussianFactor> dcsam::DCContinuousFactor::linearize ( const gtsam::Values &  continuousVals) const
inlineoverride

◆ operator=()

DCContinuousFactor& dcsam::DCContinuousFactor::operator= ( const DCContinuousFactor rhs)
inline

◆ updateDiscrete()

bool dcsam::DCContinuousFactor::updateDiscrete ( const DiscreteValues discreteVals)
inline

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