ActiveSetSolver.h
Go to the documentation of this file.
1 /* ----------------------------------------------------------------------------
2 
3  * GTSAM Copyright 2010, Georgia Tech Research Corporation,
4  * Atlanta, Georgia 30332-0415
5  * All Rights Reserved
6  * Authors: Frank Dellaert, et al. (see THANKS for the full author list)
7 
8  * See LICENSE for the license information
9 
10  * -------------------------------------------------------------------------- */
11 
19 #pragma once
20 
23 #include <boost/range/adaptor/map.hpp>
24 
25 namespace gtsam {
26 
36 template <class PROBLEM, class POLICY, class INITSOLVER>
38 public:
40  struct State {
45  bool converged;
46  size_t iterations;
49  State()
51  : values(), duals(), workingSet(), converged(false), iterations(0) {}
52 
54  State(const VectorValues& initialValues, const VectorValues& initialDuals,
55  const InequalityFactorGraph& initialWorkingSet, bool _converged,
56  size_t _iterations)
57  : values(initialValues),
58  duals(initialDuals),
59  workingSet(initialWorkingSet),
60  converged(_converged),
61  iterations(_iterations) {}
62  };
63 
64 protected:
65  const PROBLEM& problem_;
72  typedef std::vector<std::pair<Key, Matrix> > TermsContainer;
74 
75 public:
77  ActiveSetSolver(const PROBLEM& problem) : problem_(problem) {
78  equalityVariableIndex_ = VariableIndex(problem_.equalities);
79  inequalityVariableIndex_ = VariableIndex(problem_.inequalities);
80  constrainedKeys_ = problem_.equalities.keys();
81  constrainedKeys_.merge(problem_.inequalities.keys());
82  }
83 
90  std::pair<VectorValues, VectorValues> optimize(
91  const VectorValues& initialValues,
92  const VectorValues& duals = VectorValues(),
93  bool useWarmStart = false) const;
94 
99  std::pair<VectorValues, VectorValues> optimize() const;
100 
101 protected:
117  boost::tuple<double, int> computeStepSize(
119  const VectorValues& p, const double& maxAlpha) const;
120 
125  template<typename FACTOR>
127  const VariableIndex& variableIndex) const {
128  /*
129  * Iterates through each factor in the factor graph and checks
130  * whether it's active. If the factor is active it reutrns the A
131  * term of the factor.
132  */
133  TermsContainer Aterms;
134  if (variableIndex.find(key) != variableIndex.end()) {
135  for (size_t factorIx : variableIndex[key]) {
136  typename FACTOR::shared_ptr factor = graph.at(factorIx);
137  if (!factor->active())
138  continue;
139  Matrix Ai = factor->getA(factor->find(key)).transpose();
140  Aterms.push_back(std::make_pair(factor->dualKey(), Ai));
141  }
142  }
143  return Aterms;
144  }
145 
151  Key key, const InequalityFactorGraph& workingSet,
152  const VectorValues& delta) const;
153 
154 public:
155 
158  const VectorValues &delta) const;
159 
168  const InequalityFactorGraph& workingSet,
169  const VectorValues& xk = VectorValues()) const;
170 
172  State iterate(const State& state) const;
173 
176  const InequalityFactorGraph& inequalities,
177  const VectorValues& initialValues,
178  const VectorValues& duals = VectorValues(),
179  bool useWarmStart = false) const;
180 
182  int identifyLeavingConstraint(const InequalityFactorGraph& workingSet,
183  const VectorValues& lambdas) const;
184 
185 };
186 
191 template <class PROBLEM>
192 Key maxKey(const PROBLEM& problem) {
193  auto keys = problem.cost.keys();
194  Key maxKey = *std::max_element(keys.begin(), keys.end());
195  if (!problem.equalities.empty())
196  maxKey = std::max(maxKey, *problem.equalities.keys().rbegin());
197  if (!problem.inequalities.empty())
198  maxKey = std::max(maxKey, *problem.inequalities.keys().rbegin());
199  return maxKey;
200 }
201 
202 } // namespace gtsam
203 
ActiveSetSolver(const PROBLEM &problem)
Constructor.
bool converged
True if the algorithm has converged to a solution.
#define max(a, b)
Definition: datatypes.h:20
VectorValues values
current best values at each step
State iterate(const State &state) const
Iterate 1 step, return a new state with a new workingSet and values.
Eigen::MatrixXd Matrix
Definition: base/Matrix.h:43
const_iterator find(Key key) const
Find the iterator for the requested variable entry.
GaussianFactorGraph buildWorkingGraph(const InequalityFactorGraph &workingSet, const VectorValues &xk=VectorValues()) const
void merge(const FastSet &other)
Definition: FastSet.h:121
Factor graph of all LinearInequality factors.
NonlinearFactorGraph graph
Key maxKey(const PROBLEM &problem)
InequalityFactorGraph identifyActiveConstraints(const InequalityFactorGraph &inequalities, const VectorValues &initialValues, const VectorValues &duals=VectorValues(), bool useWarmStart=false) const
Identify active constraints based on initial values.
TermsContainer collectDualJacobians(Key key, const FactorGraph< FACTOR > &graph, const VariableIndex &variableIndex) const
const PROBLEM & problem_
the particular [convex] problem to solve
int identifyLeavingConstraint(const InequalityFactorGraph &workingSet, const VectorValues &lambdas) const
Identifies active constraints that shouldn&#39;t be active anymore.
State()
Default constructor.
std::pair< VectorValues, VectorValues > optimize() const
InequalityFactorGraph workingSet
boost::tuple< double, int > computeStepSize(const InequalityFactorGraph &workingSet, const VectorValues &xk, const VectorValues &p, const double &maxAlpha) const
VariableIndex inequalityVariableIndex_
Linear Factor Graph where all factors are Gaussians.
State(const VectorValues &initialValues, const VectorValues &initialDuals, const InequalityFactorGraph &initialWorkingSet, bool _converged, size_t _iterations)
Constructor with initial values.
const_iterator end() const
Iterator to the first variable entry.
GaussianFactorGraph buildDualGraph(const InequalityFactorGraph &workingSet, const VectorValues &delta) const
Just for testing...
JacobianFactor::shared_ptr createDualFactor(Key key, const InequalityFactorGraph &workingSet, const VectorValues &delta) const
traits
Definition: chartTesting.h:28
const sharedFactor at(size_t i) const
Definition: FactorGraph.h:315
This struct contains the state information for a single iteration.
float * p
VectorValues duals
current values of dual variables at each step
const KeyVector keys
boost::shared_ptr< This > shared_ptr
shared_ptr to this class
std::vector< std::pair< Key, Matrix > > TermsContainer
Vector of key matrix pairs. Matrices are usually the A term for a factor.
VariableIndex equalityVariableIndex_
std::uint64_t Key
Integer nonlinear key type.
Definition: types.h:61
Implmentation of ActiveSetSolver.


gtsam
Author(s):
autogenerated on Sat May 8 2021 02:41:36