2014-12-23 08:49:32 +08:00
|
|
|
/* ----------------------------------------------------------------------------
|
|
|
|
|
|
|
|
* GTSAM Copyright 2010, Georgia Tech Research Corporation,
|
|
|
|
* Atlanta, Georgia 30332-0415
|
|
|
|
* All Rights Reserved
|
|
|
|
* Authors: Frank Dellaert, et al. (see THANKS for the full author list)
|
|
|
|
|
|
|
|
* See LICENSE for the license information
|
|
|
|
|
|
|
|
* -------------------------------------------------------------------------- */
|
2015-02-25 11:09:31 +08:00
|
|
|
|
|
|
|
/**
|
2015-02-25 22:09:33 +08:00
|
|
|
* @file QPSolver.h
|
|
|
|
* @brief A quadratic programming solver implements the active set method
|
|
|
|
* @date Apr 15, 2014
|
|
|
|
* @author Duy-Nguyen Ta
|
2014-04-16 04:27:19 +08:00
|
|
|
*/
|
|
|
|
|
|
|
|
#pragma once
|
|
|
|
|
|
|
|
#include <gtsam/linear/VectorValues.h>
|
2014-12-09 19:13:57 +08:00
|
|
|
#include <gtsam_unstable/linear/QP.h>
|
2016-01-26 08:24:37 +08:00
|
|
|
#include <gtsam_unstable/linear/ActiveSetSolver.h>
|
|
|
|
#include <gtsam_unstable/linear/QPState.h>
|
2014-04-16 04:27:19 +08:00
|
|
|
|
2014-11-26 16:04:34 +08:00
|
|
|
#include <vector>
|
|
|
|
#include <set>
|
|
|
|
|
2014-04-16 04:27:19 +08:00
|
|
|
namespace gtsam {
|
|
|
|
/**
|
2015-02-25 11:09:31 +08:00
|
|
|
* This QPSolver uses the active set method to solve a quadratic programming problem
|
|
|
|
* defined in the QP struct.
|
|
|
|
* Note: This version of QPSolver only works with a feasible initial value.
|
2014-04-16 04:27:19 +08:00
|
|
|
*/
|
2016-01-26 20:56:52 +08:00
|
|
|
//TODO: Remove Vector Values
|
2016-01-26 08:24:37 +08:00
|
|
|
class QPSolver: public ActiveSetSolver {
|
2014-11-27 17:47:45 +08:00
|
|
|
|
2014-12-09 19:13:57 +08:00
|
|
|
const QP& qp_; //!< factor graphs of the QP problem, can't be modified!
|
2014-04-16 04:27:19 +08:00
|
|
|
|
|
|
|
public:
|
|
|
|
/// Constructor
|
2014-12-09 19:13:57 +08:00
|
|
|
QPSolver(const QP& qp);
|
|
|
|
|
|
|
|
/// Find solution with the current working set
|
|
|
|
VectorValues solveWithCurrentWorkingSet(
|
2015-02-25 11:25:26 +08:00
|
|
|
const InequalityFactorGraph& workingSet) const;
|
2014-12-09 19:13:57 +08:00
|
|
|
|
|
|
|
/// Create a dual factor
|
|
|
|
JacobianFactor::shared_ptr createDualFactor(Key key,
|
2016-01-26 08:24:37 +08:00
|
|
|
const InequalityFactorGraph& workingSet, const VectorValues& delta) const;
|
2014-12-09 19:13:57 +08:00
|
|
|
/// @}
|
2014-04-16 04:27:19 +08:00
|
|
|
|
2014-12-13 01:03:00 +08:00
|
|
|
boost::tuple<double, int> computeStepSize(
|
2015-02-25 11:25:26 +08:00
|
|
|
const InequalityFactorGraph& workingSet, const VectorValues& xk,
|
2014-11-26 16:04:34 +08:00
|
|
|
const VectorValues& p) const;
|
2014-04-16 04:27:19 +08:00
|
|
|
|
2014-12-09 19:13:57 +08:00
|
|
|
/** Iterate 1 step, return a new state with a new workingSet and values */
|
|
|
|
QPState iterate(const QPState& state) const;
|
2014-04-16 04:27:19 +08:00
|
|
|
|
2014-12-10 05:27:11 +08:00
|
|
|
/**
|
|
|
|
* Identify active constraints based on initial values.
|
|
|
|
*/
|
2015-02-25 11:25:26 +08:00
|
|
|
InequalityFactorGraph identifyActiveConstraints(
|
|
|
|
const InequalityFactorGraph& inequalities,
|
2016-01-26 08:24:37 +08:00
|
|
|
const VectorValues& initialValues, const VectorValues& duals =
|
|
|
|
VectorValues(), bool useWarmStart = true) const;
|
2014-12-10 05:27:11 +08:00
|
|
|
|
2014-05-02 11:55:43 +08:00
|
|
|
/** Optimize with a provided initial values
|
|
|
|
* For this version, it is the responsibility of the caller to provide
|
2015-02-25 11:09:31 +08:00
|
|
|
* a feasible initial value, otherwise, an exception will be thrown.
|
Support non positive definite Hessian factors while doing EliminatePreferCholesky with some constrained factors.
Currently, when eliminating a constrained variable, EliminatePreferCholesky converts every other factors to JacobianFactor before doing the special QR factorization for constrained variables. Unfortunately, after a constrained nonlinear graph is linearized, new hessian factors from constraints, multiplied with the dual variable (-lambda*\hessian{c} terms in the Lagrangian objective function), might become negative definite, thus cannot be converted to JacobianFactors.
Following EliminateCholesky, this version of EliminatePreferCholesky for constrained var gathers all unconstrained factors into a big joint HessianFactor before converting it into a JacobianFactor to be eliminiated by QR together with the other constrained factors.
Of course, this might not solve the non-positive-definite problem entirely, because (1) the original hessian factors might be non-positive definite and (2) large strange value of lambdas might cause the joint factor non-positive definite [is this true?]. But at least, this will help in typical cases.
2014-05-04 06:04:37 +08:00
|
|
|
* @return a pair of <primal, dual> solutions
|
2014-05-02 11:55:43 +08:00
|
|
|
*/
|
2014-11-26 16:04:34 +08:00
|
|
|
std::pair<VectorValues, VectorValues> optimize(
|
2016-01-26 08:24:37 +08:00
|
|
|
const VectorValues& initialValues, const VectorValues& duals =
|
|
|
|
VectorValues(), bool useWarmStart = true) const;
|
2014-04-16 04:27:19 +08:00
|
|
|
|
2015-02-25 10:49:27 +08:00
|
|
|
};
|
|
|
|
|
2014-04-16 04:27:19 +08:00
|
|
|
} /* namespace gtsam */
|