diff --git a/gtsam_unstable/linear/QPInitSolver.h b/gtsam_unstable/linear/QPInitSolver.h new file mode 100644 index 000000000..203cc616a --- /dev/null +++ b/gtsam_unstable/linear/QPInitSolver.h @@ -0,0 +1,45 @@ +/** + * @file QPInitSolver.h + * @brief This QPInitSolver implements the strategy in Matlab. + * @author Duy Nguyen Ta + * @author Ivan Dario Jimenez + * @date 6/16/16 + */ + +#pragma once + +#include + +namespace gtsam { + +/** + * This class finds a feasible solution for a QP problem. + * This uses the Matlab strategy for initialization + * For details, see + * http://www.mathworks.com/help/optim/ug/quadratic-programming-algorithms.html#brrzwpf-22 + */ +class QPInitSolver { + const QP& qp_; +public: + /// Constructor with a QP problem + QPInitSolver(const QP& qp) : qp_(qp) {} + + /** + * @return a feasible initialization point + */ + VectorValues solve() const { + // Make an LP with any linear cost function. It doesn't matter for + // initialization. + LP initProblem; + // make an unrelated key for a random variable cost + Key newKey = maxKey(qp_) + 1; + initProblem.cost = LinearCost(newKey, Vector::Ones(1)); + initProblem.equalities = qp_.equalities; + initProblem.inequalities = qp_.inequalities; + LPInitSolver initSolver(initProblem); + return initSolver.solve(); + } +}; + + +} \ No newline at end of file diff --git a/gtsam_unstable/linear/QPSolver.cpp b/gtsam_unstable/linear/QPSolver.cpp index 703ce2faa..c1984a75d 100644 --- a/gtsam_unstable/linear/QPSolver.cpp +++ b/gtsam_unstable/linear/QPSolver.cpp @@ -21,8 +21,8 @@ #include #include #include +#include #include -#include using namespace std; @@ -169,16 +169,8 @@ pair QPSolver::optimize( //****************************************************************************** pair QPSolver::optimize() const { - //Make an LP with any linear cost function. It doesn't matter for initialization. - LP initProblem; - // make an unrelated key for a random variable cost - Key newKey = maxKey(qp_) + 1; - initProblem.cost = LinearCost(newKey, Vector::Ones(1)); - initProblem.equalities = qp_.equalities; - initProblem.inequalities = qp_.inequalities; - LPInitSolver initSolver(initProblem); + QPInitSolver initSolver(qp_); VectorValues initValues = initSolver.solve(); - return optimize(initValues); } diff --git a/gtsam_unstable/linear/QPSolver.h b/gtsam_unstable/linear/QPSolver.h index 9c67b9985..6fa60b048 100644 --- a/gtsam_unstable/linear/QPSolver.h +++ b/gtsam_unstable/linear/QPSolver.h @@ -96,9 +96,6 @@ public: /** * For this version the caller will not have to provide an initial value - * Uses the matlab strategy for initialization - * See http://www.mathworks.com/help/optim/ug/quadratic-programming-algorithms.html#brrzwpf-22 - * For details * @return a pair of solutions */ std::pair optimize() const;