TVM  0.9.4
QLDLeastSquareSolver.h
Go to the documentation of this file.
1 /* Copyright 2017-2020 CNRS-AIST JRL and CNRS-UM LIRMM */
2 
3 #pragma once
4 
6 
7 #include <eigen-qld/QLDDirect.h>
8 
9 #include <Eigen/QR>
10 
11 namespace tvm
12 {
13 
14 namespace solver
15 {
16 class QLDLSSolverFactory;
17 
20 {
21  TVM_ADD_NON_DEFAULT_OPTION(big_number, constant::big_number)
22  TVM_ADD_NON_DEFAULT_OPTION(cholesky, false)
23  TVM_ADD_NON_DEFAULT_OPTION(choleskyDamping, 1e-8)
25  TVM_ADD_NON_DEFAULT_OPTION(verbose, false)
26 public:
28 };
29 
32 {
33 public:
35 
36 protected:
37  void initializeBuild_(int nObj, int nEq, int nIneq, bool useBounds) override;
38  ImpactFromChanges resize_(int nObj, int nEq, int nIneq, bool useBounds) override;
39  void addBound_(LinearConstraintPtr bound, RangePtr range, bool first) override;
42  void addObjective_(LinearConstraintPtr cstr, SolvingRequirementsPtr req, double additionalWeight) override;
43  void setMinimumNorm_() override;
44  void resetBounds_() override;
45  void preAssignmentProcess_() override;
46  void postAssignmentProcess_() override;
47  bool solve_() override;
48  virtual const Eigen::VectorXd & result_() const override;
49  bool handleDoubleSidedConstraint_() const override { return false; }
53  void removeBounds_(const Range & r) override;
58 
59  void applyImpactLogic(ImpactFromChanges & impact) override;
60 
61  void printProblemData_() const override;
62  void printDiagnostic_() const override;
63 
64 private:
65  using VectorXdTail = decltype(Eigen::VectorXd().tail(1));
66  using MatrixXdBottom = decltype(Eigen::MatrixXd().bottomRows(1));
67 
68  Eigen::MatrixXd D_; // We have Q = D^T D
69  Eigen::VectorXd e_; // We have c = D^t e
70  Eigen::MatrixXd Q_;
71  Eigen::VectorXd c_;
72  Eigen::MatrixXd A_;
73  Eigen::VectorXd b_;
74  Eigen::VectorXd xl_;
75  Eigen::VectorXd xu_;
76 
77  MatrixXdBottom Aineq_; // part of A_ corresponding to inequality constraints
78  VectorXdTail bineq_; // part of b_ corresponding to inequality constraints
79 
80  Eigen::QLDDirect qld_;
81  Eigen::HouseholderQR<Eigen::MatrixXd> qr_; // TODO add option for ColPiv variant
82 
83  bool autoMinNorm_;
84  bool underspecifiedObj_; // true when nObj<n
85 
86  // options
87  double big_number_;
88  double eps_;
89  bool cholesky_; // compute the Cholesky decomposition before calling the solver.
90  double choleskyDamping_; // if nObj<n, the cholesky factor R is trapezoidal. A multiple of
91  // the identity is used to make it triangular using this value.
92 };
93 
98 {
99 public:
100  std::unique_ptr<abstract::LSSolverFactory> clone() const override;
101 
103  QLDLSSolverFactory(const QLDLSSolverOptions & options = {});
104 
105  std::unique_ptr<abstract::LeastSquareSolver> createSolver() const override;
106 
107 private:
108  QLDLSSolverOptions options_;
109 };
110 
111 } // namespace solver
112 
113 } // namespace tvm
#define TVM_ADD_NON_DEFAULT_OPTION(optionName, defaultValue)
Definition: Option.h:30
#define TVM_DLLAPI
Definition: api.h:35
Definition: Range.h:19
Definition: LinearConstraint.h:56
Definition: AssignmentTarget.h:37
Definition: QLDLeastSquareSolver.h:98
std::unique_ptr< abstract::LSSolverFactory > clone() const override
QLDLSSolverFactory(const QLDLSSolverOptions &options={})
std::unique_ptr< abstract::LeastSquareSolver > createSolver() const override
Definition: QLDLeastSquareSolver.h:20
Definition: QLDLeastSquareSolver.h:32
Range nextInequalityConstraintRange_(const constraint::abstract::LinearConstraint &cstr) const override
void addObjective_(LinearConstraintPtr cstr, SolvingRequirementsPtr req, double additionalWeight) override
bool handleDoubleSidedConstraint_() const override
Definition: QLDLeastSquareSolver.h:49
QLDLeastSquareSolver(const QLDLSSolverOptions &options={})
void updateBoundTargetData(scheme::internal::AssignmentTarget &target) override
virtual const Eigen::VectorXd & result_() const override
void addBound_(LinearConstraintPtr bound, RangePtr range, bool first) override
void printProblemData_() const override
void removeBounds_(const Range &r) override
void updateObjectiveTargetData(scheme::internal::AssignmentTarget &target) override
void printDiagnostic_() const override
Range nextObjectiveRange_(const constraint::abstract::LinearConstraint &cstr) const override
void updateEqualityTargetData(scheme::internal::AssignmentTarget &target) override
void addIneqalityConstraint_(LinearConstraintPtr cstr) override
void initializeBuild_(int nObj, int nEq, int nIneq, bool useBounds) override
ImpactFromChanges resize_(int nObj, int nEq, int nIneq, bool useBounds) override
void addEqualityConstraint_(LinearConstraintPtr cstr) override
void postAssignmentProcess_() override
Range nextEqualityConstraintRange_(const constraint::abstract::LinearConstraint &cstr) const override
void updateInequalityTargetData(scheme::internal::AssignmentTarget &target) override
void applyImpactLogic(ImpactFromChanges &impact) override
Definition: LeastSquareSolver.h:220
Definition: LeastSquareSolver.h:37
Definition: Clock.h:12
std::shared_ptr< constraint::abstract::LinearConstraint > LinearConstraintPtr
Definition: defs.h:59
std::shared_ptr< Range > RangePtr
Definition: defs.h:61
std::shared_ptr< requirements::SolvingRequirementsWithCallbacks > SolvingRequirementsPtr
Definition: defs.h:63