Classes | Public Member Functions | Protected Types | Protected Member Functions | Protected Attributes | List of all members
gtsam::ActiveSetSolver< PROBLEM, POLICY, INITSOLVER > Class Template Reference

#include <ActiveSetSolver.h>

Classes

struct  State
 This struct contains the state information for a single iteration. More...
 

Public Member Functions

 ActiveSetSolver (const PROBLEM &problem)
 Constructor. More...
 
GaussianFactorGraph buildDualGraph (const InequalityFactorGraph &workingSet, const VectorValues &delta) const
 Just for testing... More...
 
GaussianFactorGraph buildWorkingGraph (const InequalityFactorGraph &workingSet, const VectorValues &xk=VectorValues()) const
 
InequalityFactorGraph identifyActiveConstraints (const InequalityFactorGraph &inequalities, const VectorValues &initialValues, const VectorValues &duals=VectorValues(), bool useWarmStart=false) const
 Identify active constraints based on initial values. More...
 
int identifyLeavingConstraint (const InequalityFactorGraph &workingSet, const VectorValues &lambdas) const
 Identifies active constraints that shouldn't be active anymore. More...
 
State iterate (const State &state) const
 Iterate 1 step, return a new state with a new workingSet and values. More...
 
std::pair< VectorValues, VectorValuesoptimize (const VectorValues &initialValues, const VectorValues &duals=VectorValues(), bool useWarmStart=false) const
 
std::pair< VectorValues, VectorValuesoptimize () const
 

Protected Types

typedef std::vector< std::pair< Key, Matrix > > TermsContainer
 Vector of key matrix pairs. Matrices are usually the A term for a factor. More...
 

Protected Member Functions

template<typename FACTOR >
TermsContainer collectDualJacobians (Key key, const FactorGraph< FACTOR > &graph, const VariableIndex &variableIndex) const
 
boost::tuple< double, intcomputeStepSize (const InequalityFactorGraph &workingSet, const VectorValues &xk, const VectorValues &p, const double &maxAlpha) const
 
JacobianFactor::shared_ptr createDualFactor (Key key, const InequalityFactorGraph &workingSet, const VectorValues &delta) const
 

Protected Attributes

KeySet constrainedKeys_
 
VariableIndex equalityVariableIndex_
 
VariableIndex inequalityVariableIndex_
 
const PROBLEM & problem_
 the particular [convex] problem to solve More...
 

Detailed Description

template<class PROBLEM, class POLICY, class INITSOLVER>
class gtsam::ActiveSetSolver< PROBLEM, POLICY, INITSOLVER >

This class implements the active set algorithm for solving convex Programming problems.

Template Parameters
PROBLEMType of the problem to solve, e.g. LP (linear program) or QP (quadratic program).
POLICYspecific detail policy tailored for the particular program
INITSOLVERSolver for an initial feasible solution of this problem.

Definition at line 37 of file ActiveSetSolver.h.

Member Typedef Documentation

template<class PROBLEM , class POLICY , class INITSOLVER >
typedef std::vector<std::pair<Key, Matrix> > gtsam::ActiveSetSolver< PROBLEM, POLICY, INITSOLVER >::TermsContainer
protected

Vector of key matrix pairs. Matrices are usually the A term for a factor.

Definition at line 73 of file ActiveSetSolver.h.

Constructor & Destructor Documentation

template<class PROBLEM , class POLICY , class INITSOLVER >
gtsam::ActiveSetSolver< PROBLEM, POLICY, INITSOLVER >::ActiveSetSolver ( const PROBLEM &  problem)
inline

Constructor.

Definition at line 77 of file ActiveSetSolver.h.

Member Function Documentation

template<class PROBLEM , class POLICY , class INITSOLVER >
GaussianFactorGraph gtsam::ActiveSetSolver< PROBLEM, POLICY, INITSOLVER >::buildDualGraph ( const InequalityFactorGraph workingSet,
const VectorValues delta 
) const

Just for testing...

Builds a dual graph from the current working set.

template<class PROBLEM , class POLICY , class INITSOLVER >
GaussianFactorGraph gtsam::ActiveSetSolver< PROBLEM, POLICY, INITSOLVER >::buildWorkingGraph ( const InequalityFactorGraph workingSet,
const VectorValues xk = VectorValues() 
) const

Build a working graph of cost, equality and active inequality constraints to solve at each iteration.

Parameters
workingSetthe collection of all cost and constrained factors
xkcurrent solution, used to build a special quadratic cost in LP
Returns
a new better solution
template<class PROBLEM , class POLICY , class INITSOLVER >
template<typename FACTOR >
TermsContainer gtsam::ActiveSetSolver< PROBLEM, POLICY, INITSOLVER >::collectDualJacobians ( Key  key,
const FactorGraph< FACTOR > &  graph,
const VariableIndex variableIndex 
) const
inlineprotected

Finds the active constraints in the given factor graph and returns the Dual Jacobians used to build a dual factor graph.

Definition at line 126 of file ActiveSetSolver.h.

template<class PROBLEM , class POLICY , class INITSOLVER >
boost::tuple<double, int> gtsam::ActiveSetSolver< PROBLEM, POLICY, INITSOLVER >::computeStepSize ( const InequalityFactorGraph workingSet,
const VectorValues xk,
const VectorValues p,
const double &  maxAlpha 
) const
protected

Compute minimum step size alpha to move from the current point xk to the next feasible point along a direction p: x' = xk + alpha*p, where alpha [0,maxAlpha].

For QP, maxAlpha = 1. For LP: maxAlpha = Inf.

Returns
a tuple of (minAlpha, closestFactorIndex) where closestFactorIndex is the closest inactive inequality constraint that blocks xk to move further and that has the minimum alpha, or (-1, maxAlpha) if there is no such inactive blocking constraint.

If there is a blocking constraint, the closest one will be added to the working set and become active in the next iteration.

template<class PROBLEM , class POLICY , class INITSOLVER >
JacobianFactor::shared_ptr gtsam::ActiveSetSolver< PROBLEM, POLICY, INITSOLVER >::createDualFactor ( Key  key,
const InequalityFactorGraph workingSet,
const VectorValues delta 
) const
protected

Creates a dual factor from the current workingSet and the key of the the variable used to created the dual factor.

template<class PROBLEM , class POLICY , class INITSOLVER >
InequalityFactorGraph gtsam::ActiveSetSolver< PROBLEM, POLICY, INITSOLVER >::identifyActiveConstraints ( const InequalityFactorGraph inequalities,
const VectorValues initialValues,
const VectorValues duals = VectorValues(),
bool  useWarmStart = false 
) const

Identify active constraints based on initial values.

template<class PROBLEM , class POLICY , class INITSOLVER >
int gtsam::ActiveSetSolver< PROBLEM, POLICY, INITSOLVER >::identifyLeavingConstraint ( const InequalityFactorGraph workingSet,
const VectorValues lambdas 
) const

Identifies active constraints that shouldn't be active anymore.

template<class PROBLEM , class POLICY , class INITSOLVER >
State gtsam::ActiveSetSolver< PROBLEM, POLICY, INITSOLVER >::iterate ( const State state) const

Iterate 1 step, return a new state with a new workingSet and values.

template<class PROBLEM , class POLICY , class INITSOLVER >
std::pair<VectorValues, VectorValues> gtsam::ActiveSetSolver< PROBLEM, POLICY, INITSOLVER >::optimize ( const VectorValues initialValues,
const VectorValues duals = VectorValues(),
bool  useWarmStart = false 
) const

Optimize with provided initial values For this version, it is the responsibility of the caller to provide a feasible initial value, otherwise, an exception will be thrown.

Returns
a pair of <primal, dual> solutions
template<class PROBLEM , class POLICY , class INITSOLVER >
std::pair<VectorValues, VectorValues> gtsam::ActiveSetSolver< PROBLEM, POLICY, INITSOLVER >::optimize ( ) const

For this version the caller will not have to provide an initial value

Returns
a pair of <primal, dual> solutions

Member Data Documentation

template<class PROBLEM , class POLICY , class INITSOLVER >
KeySet gtsam::ActiveSetSolver< PROBLEM, POLICY, INITSOLVER >::constrainedKeys_
protected

all constrained keys, will become factors in dual graphs

Definition at line 69 of file ActiveSetSolver.h.

template<class PROBLEM , class POLICY , class INITSOLVER >
VariableIndex gtsam::ActiveSetSolver< PROBLEM, POLICY, INITSOLVER >::equalityVariableIndex_
protected

Definition at line 66 of file ActiveSetSolver.h.

template<class PROBLEM , class POLICY , class INITSOLVER >
VariableIndex gtsam::ActiveSetSolver< PROBLEM, POLICY, INITSOLVER >::inequalityVariableIndex_
protected

index to corresponding factors to build dual graphs

Definition at line 66 of file ActiveSetSolver.h.

template<class PROBLEM , class POLICY , class INITSOLVER >
const PROBLEM& gtsam::ActiveSetSolver< PROBLEM, POLICY, INITSOLVER >::problem_
protected

the particular [convex] problem to solve

Definition at line 65 of file ActiveSetSolver.h.


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


gtsam
Author(s):
autogenerated on Sat May 8 2021 02:58:03