#include <DCSAM.h>
|
| | DCSAM () |
| |
| | DCSAM (const gtsam::ISAM2Params &isam_params) |
| |
| void | update (const gtsam::NonlinearFactorGraph &graph, const gtsam::DiscreteFactorGraph &dfg, const DCFactorGraph &dcfg, const gtsam::Values &initialGuessContinuous=gtsam::Values(), const DiscreteValues &initialGuessDiscrete=DiscreteValues()) |
| |
| void | update (const HybridFactorGraph &hfg, const gtsam::Values &initialGuessContinuous=gtsam::Values(), const DiscreteValues &initialGuessDiscrete=DiscreteValues()) |
| |
| void | update (const HybridFactorGraph &hfg, const DiscreteValues &initialGuessDiscrete) |
| |
| void | update () |
| |
| void | updateDiscrete (const gtsam::DiscreteFactorGraph &graph, const gtsam::Values &continuousVals, const DiscreteValues &discreteVals) |
| |
| void | updateDiscreteInfo (const gtsam::Values &continuousVals, const DiscreteValues &discreteVals) |
| |
| void | updateContinuous () |
| |
| void | updateContinuousInfo (const DiscreteValues &discreteVals, const gtsam::NonlinearFactorGraph &newFactors, const gtsam::Values &initialGuess) |
| |
| DiscreteValues | solveDiscrete () const |
| |
| DCValues | calculateEstimate () const |
| |
| DCMarginals | getMarginals (const gtsam::NonlinearFactorGraph &graph, const gtsam::Values &continuousEst, const gtsam::DiscreteFactorGraph &dfg) |
| |
| gtsam::DiscreteFactorGraph | getDiscreteFactorGraph () const |
| |
| gtsam::NonlinearFactorGraph | getNonlinearFactorGraph () const |
| |
◆ DCSAM() [1/2]
◆ DCSAM() [2/2]
| dcsam::DCSAM::DCSAM |
( |
const gtsam::ISAM2Params & |
isam_params | ) |
|
|
explicit |
◆ calculateEstimate()
| DCValues dcsam::DCSAM::calculateEstimate |
( |
| ) |
const |
This is the primary function used to extract an estimate from the solver. Internally, calls isam_.calculateEstimate() and dfg_.optimize() to obtain an estimate for the continuous (resp. discrete) variables and packages them into a DCValues pair as (continuousVals, discreteVals).
- Returns
- a DCValues object containing an estimate of the most probable assignment to the continuous (DCValues.continuous) and discrete (DCValues.discrete) variables.
◆ getDiscreteFactorGraph()
| gtsam::DiscreteFactorGraph dcsam::DCSAM::getDiscreteFactorGraph |
( |
| ) |
const |
|
inline |
◆ getMarginals()
| DCMarginals dcsam::DCSAM::getMarginals |
( |
const gtsam::NonlinearFactorGraph & |
graph, |
|
|
const gtsam::Values & |
continuousEst, |
|
|
const gtsam::DiscreteFactorGraph & |
dfg |
|
) |
| |
Used to obtain the marginals from the solver.
NOTE: not obviously correct (see DCSAM.cpp implementation) at the moment. Should perhaps retrieve the marginals for the factor graph obtained as isam_.getFactorsUnsafe() and dfg_ rather than taking as a parameter? I think this was originally intended to mimic the gtsam Marginals class.
- Parameters
-
◆ getNonlinearFactorGraph()
| gtsam::NonlinearFactorGraph dcsam::DCSAM::getNonlinearFactorGraph |
( |
| ) |
const |
|
inline |
◆ solveDiscrete()
Solve for discrete variables given continuous variables. Internally, calls dfg_.optimize()
- Returns
- an assignment (DiscreteValues) to the discrete variables in the graph.
◆ update() [1/4]
| void dcsam::DCSAM::update |
( |
| ) |
|
Simply used to call update without any new factors. Runs an iteration of optimization.
◆ update() [2/4]
| void dcsam::DCSAM::update |
( |
const gtsam::NonlinearFactorGraph & |
graph, |
|
|
const gtsam::DiscreteFactorGraph & |
dfg, |
|
|
const DCFactorGraph & |
dcfg, |
|
|
const gtsam::Values & |
initialGuessContinuous = gtsam::Values(), |
|
|
const DiscreteValues & |
initialGuessDiscrete = DiscreteValues() |
|
) |
| |
For this solver, runs an iteration of alternating minimization between discrete and continuous variables, adding any user-supplied factors (with initial guess) first.
- Adds new discrete factors (if any) as supplied by a user to the discrete factor graph, then adds any discrete-continuous factors to the discrete factor graph, appropriately initializing their continuous variables to those from the last solve and any supplied by the initial guess.
- Update the solution for the discrete variables.
- For all new discrete-continuous factors to be passed to the continuous solver, update/set the latest discrete variables (prior to adding).
- In one step: add new factors, new values, and earmarked old factor keys to iSAM. Specifically, loop over DC factors already in iSAM, updating their discrete information, then call isam_.update() with the (initialized) new DC factors, any new continuous factors, and the initial guess to be supplied.
- Calculate the latest continuous variables from iSAM.
- Update the discrete factors in the discrete factor graph dfg_ with the latest information from the continuous solve.
- Parameters
-
| graph | - a gtsam::NonlinearFactorGraph containing any continuous-only factors to add. |
| dfg | - a gtsam::DiscreteFactorGraph containing any discrete-only factors to add. |
| dcfg | - a DCFactorGraph containing any joint discrete-continuous factors to add. |
| initialGuess | - an initial guess for any new continuous keys that. appear in the updated factors (or if one wants to force override previously obtained continuous values). |
◆ update() [3/4]
Inline convenience function to allow "skipping" the initial guess for continuous variables while adding an initial guess for discrete variables.
◆ update() [4/4]
A HybridFactorGraph is a container holding a NonlinearFactorGraph, a DiscreteFactorGraph, and a DCFactorGraph, so internally this function simply issues a call to update with these internal graphs passed as parameters: that is:
update(hfg.nonlinearGraph(), hfg.discreteGraph(), hfg.dcGraph(), initialGuess);
◆ updateContinuous()
| void dcsam::DCSAM::updateContinuous |
( |
| ) |
|
At the moment, this just calls isam_.update() internally This could, for example, be used if one wanted to hold the discrete variables constant and perform multiple iterations of updates to the continuous variables.
NOTE: this function behaves quite differently from the similarly named updateDiscrete function, maybe we consider refactoring some of these function names.
◆ updateContinuousInfo()
| void dcsam::DCSAM::updateContinuousInfo |
( |
const DiscreteValues & |
discreteVals, |
|
|
const gtsam::NonlinearFactorGraph & |
newFactors, |
|
|
const gtsam::Values & |
initialGuess |
|
) |
| |
Given the latest discrete values (dcValues), a set of new factors (newFactors), and an initial guess for any new keys (initialGuess), this function updates the continuous values stored in any DC factors (in the member isam_ instance), marks any affected keys as such, and calls isam_.update with the new factors and initial guess. See implementation for more detail.
NOTE: this is another function that could perhaps be named better.
◆ updateDiscrete()
| void dcsam::DCSAM::updateDiscrete |
( |
const gtsam::DiscreteFactorGraph & |
graph = gtsam::DiscreteFactorGraph(), |
|
|
const gtsam::Values & |
continuousVals = gtsam::Values(), |
|
|
const DiscreteValues & |
discreteVals = DiscreteValues() |
|
) |
| |
Add factors in graph to member discrete factor graph dfg_, then update any stored continuous variables using those in values by calling updateDiscreteInfo(values).
NOTE: could this be combined with updateDiscreteInfo or do these definitely need to be separate?
- Parameters
-
| graph | - a discrete factor graph containing the factors to add |
| values | - an assignment to the continuous variables (or subset thereof). |
◆ updateDiscreteInfo()
| void dcsam::DCSAM::updateDiscreteInfo |
( |
const gtsam::Values & |
continuousVals, |
|
|
const DiscreteValues & |
discreteVals |
|
) |
| |
For any factors in dfg_, update their stored local continuous information with the values from values.
NOTE: could this be combined with updateDiscrete or do these definitely need to be separate?
- Parameters
-
| values | - an assignment to the continuous variables (or subset thereof). |
The documentation for this class was generated from the following files: