24 #define Template template <class PROBLEM, class POLICY, class INITSOLVER> 25 #define This ActiveSetSolver<PROBLEM, POLICY, INITSOLVER> 46 Template boost::tuple<double, int> This::computeStepSize(
47 const InequalityFactorGraph& workingSet,
const VectorValues& xk,
48 const VectorValues&
p,
const double& maxAlpha)
const {
49 double minAlpha = maxAlpha;
50 int closestFactorIx = -1;
51 for (
size_t factorIx = 0; factorIx < workingSet.size(); ++factorIx) {
53 double b = factor->getb()[0];
55 if (!factor->active()) {
57 double aTp = factor->dotProductRow(p);
64 double aTx = factor->dotProductRow(xk);
67 double alpha = (b - aTx) / aTp;
69 if (alpha < minAlpha) {
70 closestFactorIx = factorIx;
113 Template int This::identifyLeavingConstraint(
114 const InequalityFactorGraph& workingSet,
115 const VectorValues& lambdas)
const {
116 int worstFactorIx = -1;
119 double maxLambda = 0.0;
120 for (
size_t factorIx = 0; factorIx < workingSet.size(); ++factorIx) {
122 if (factor->active()) {
123 double lambda = lambdas.at(factor->dualKey())[0];
124 if (lambda > maxLambda) {
125 worstFactorIx = factorIx;
130 return worstFactorIx;
135 Key key,
const InequalityFactorGraph& workingSet,
136 const VectorValues&
delta)
const {
139 TermsContainer Aterms = collectDualJacobians<LinearEquality>(
140 key, problem_.equalities, equalityVariableIndex_);
141 TermsContainer AtermsInequalities = collectDualJacobians<LinearInequality>(
142 key, workingSet, inequalityVariableIndex_);
143 Aterms.insert(Aterms.end(), AtermsInequalities.begin(),
144 AtermsInequalities.end());
147 if (Aterms.size() > 0) {
148 Vector b = problem_.costGradient(key, delta);
150 return boost::make_shared<JacobianFactor>(Aterms,
b);
168 Template GaussianFactorGraph This::buildDualGraph(
169 const InequalityFactorGraph& workingSet,
const VectorValues& delta)
const {
170 GaussianFactorGraph dualGraph;
171 for (
Key key : constrainedKeys_) {
173 auto dualFactor = createDualFactor(key, workingSet, delta);
174 if (dualFactor) dualGraph.push_back(dualFactor);
181 This::buildWorkingGraph(
const InequalityFactorGraph& workingSet,
182 const VectorValues& xk)
const {
183 GaussianFactorGraph workingGraph;
184 workingGraph.push_back(POLICY::buildCostFunction(problem_, xk));
185 workingGraph.push_back(problem_.equalities);
187 if (factor->active()) workingGraph.push_back(factor);
196 auto workingGraph = buildWorkingGraph(state.workingSet, state.values);
197 VectorValues newValues = workingGraph.optimize();
201 if (newValues.equals(state.values, 1
e-7)) {
203 auto dualGraph = buildDualGraph(state.workingSet, newValues);
204 VectorValues duals = dualGraph.optimize();
205 int leavingFactor = identifyLeavingConstraint(state.workingSet, duals);
207 if (leavingFactor < 0) {
208 return State(newValues, duals, state.workingSet,
true,
209 state.iterations + 1);
212 InequalityFactorGraph newWorkingSet = state.workingSet;
213 newWorkingSet.at(leavingFactor)->inactivate();
214 return State(newValues, duals, newWorkingSet,
false,
215 state.iterations + 1);
222 VectorValues p = newValues - state.values;
223 boost::tie(alpha, factorIx) =
224 computeStepSize(state.workingSet, state.values, p, POLICY::maxAlpha);
226 InequalityFactorGraph newWorkingSet = state.workingSet;
228 newWorkingSet.at(factorIx)->activate();
230 newValues = state.values + alpha *
p;
231 return State(newValues, state.duals, newWorkingSet,
false,
232 state.iterations + 1);
237 Template InequalityFactorGraph This::identifyActiveConstraints(
238 const InequalityFactorGraph& inequalities,
239 const VectorValues& initialValues,
const VectorValues& duals,
240 bool useWarmStart)
const {
241 InequalityFactorGraph workingSet;
244 if (useWarmStart && duals.size() > 0) {
245 if (duals.exists(workingFactor->dualKey())) workingFactor->activate();
246 else workingFactor->inactivate();
248 double error = workingFactor->error(initialValues);
250 if (error > 0)
throw InfeasibleInitialValues();
252 workingFactor->activate();
254 workingFactor->inactivate();
256 workingSet.push_back(workingFactor);
263 const VectorValues& initialValues,
const VectorValues& duals,
264 bool useWarmStart)
const {
266 InequalityFactorGraph workingSet = identifyActiveConstraints(
267 problem_.inequalities, initialValues, duals, useWarmStart);
268 State state(initialValues, duals, workingSet,
false, 0);
271 while (!state.converged) state = iterate(state);
273 return std::make_pair(state.values, state.duals);
278 INITSOLVER initSolver(problem_);
279 VectorValues initValues = initSolver.solve();
Exception thrown when given Infeasible Initial Values.
Point3 optimize(const NonlinearFactorGraph &graph, const Values &values, Key landmarkKey)
Tuple< Args... > make_tuple(Args...args)
Creates a tuple object, deducing the target type from the types of arguments.
Array< double, 1, 3 > e(1./3., 0.5, 2.)
cout<< "The eigenvalues of A are:"<< endl<< ces.eigenvalues()<< endl;cout<< "The matrix of eigenvectors, V, is:"<< endl<< ces.eigenvectors()<< endl<< endl;complex< float > lambda
internal::DoglegState State
int optimize(const SfmData &db, const NonlinearFactorGraph &graph, const Values &initial, bool separateCalibration=false)
boost::shared_ptr< This > shared_ptr
shared_ptr to this class
boost::shared_ptr< This > shared_ptr
shared_ptr to this class
std::uint64_t Key
Integer nonlinear key type.