forked from RobotLocomotion/drake
-
Notifications
You must be signed in to change notification settings - Fork 0
/
Copy pathcsdp_solver.h
99 lines (90 loc) · 2.92 KB
/
csdp_solver.h
1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
33
34
35
36
37
38
39
40
41
42
43
44
45
46
47
48
49
50
51
52
53
54
55
56
57
58
59
60
61
62
63
64
65
66
67
68
69
70
71
72
73
74
75
76
77
78
79
80
81
82
83
84
85
86
87
88
89
90
91
92
93
94
95
96
97
98
99
#pragma once
#include "drake/common/drake_copyable.h"
#include "drake/solvers/sdpa_free_format.h"
#include "drake/solvers/solver_base.h"
namespace drake {
namespace solvers {
/**
* The CSDP solver details after calling Solve() function. The user can call
* MathematicalProgramResult::get_solver_details<CsdpSolver>() to obtain the
* details.
*/
struct CsdpSolverDetails {
/** Refer to the Return Codes section of CSDP 6.2.0 User's Guide for
* explanation on the return code. Some of the common return codes are
*
* 0 Problem is solved to optimality.
* 1 Problem is primal infeasible.
* 2 Problem is dual infeasible.
* 3 Problem solved to near optimality.
* 4 Maximum iterations reached.
* 5 Stuck at edge of primal feasibility.
* 6 Stuck at edge of dual feasibility.
* 7 Lack of progress.
* 8 X, Z, or O is singular.
* 9 NaN or Inf values encountered.
*/
int return_code{};
/** The primal objective value. */
double primal_objective{};
/** The dual objective value. */
double dual_objective{};
/**
* CSDP solves a primal problem of the form
*
* max tr(C*X)
* s.t tr(Aᵢ*X) = aᵢ
* X ≽ 0
*
* The dual form is
*
* min aᵀy
* s.t ∑ᵢ yᵢAᵢ - C = Z
* Z ≽ 0
*
* y, Z are the variables for the dual problem.
* y_val, Z_val are the solutions to the dual problem.
*/
Eigen::VectorXd y_val;
Eigen::SparseMatrix<double> Z_val;
};
/**
* Wrap CSDP solver such that it can solve a
* drake::solvers::MathematicalProgram.
* @note CSDP doesn't accept free variables, while
* drake::solvers::MathematicalProgram does. In order to convert
* MathematicalProgram into CSDP format, we provide several approaches to remove
* free variables. You can set the approach through
* @code{cc}
* SolverOptions solver_options;
* solver_options.SetOption(CsdpSolver::id(),
* "drake::RemoveFreeVariableMethod",
* static_cast<int>(RemoveFreeVariableMethod::kNullspace));
* CsdpSolver solver;
* auto result = solver.Solve(prog, std::nullopt, solver_options);
* @endcode
* For more details, check out RemoveFreeVariableMethod.
*/
class CsdpSolver final : public SolverBase {
public:
DRAKE_NO_COPY_NO_MOVE_NO_ASSIGN(CsdpSolver);
/** Default constructor */
CsdpSolver();
~CsdpSolver() final;
/// @name Static versions of the instance methods with similar names.
//@{
static SolverId id();
static bool is_available();
static bool is_enabled();
static bool ProgramAttributesSatisfied(const MathematicalProgram&);
//@}
// A using-declaration adds these methods into our class's Doxygen.
using SolverBase::Solve;
using Details = CsdpSolverDetails;
private:
void DoSolve2(const MathematicalProgram&, const Eigen::VectorXd&,
internal::SpecificOptions*,
MathematicalProgramResult*) const final;
};
} // namespace solvers
} // namespace drake