Skip to content

Commit

Permalink
[solvers] Support IBEX Solver options
Browse files Browse the repository at this point in the history
  • Loading branch information
soonho-tri committed Aug 23, 2021
1 parent 9d0ccfb commit ed39751
Show file tree
Hide file tree
Showing 5 changed files with 449 additions and 27 deletions.
1 change: 1 addition & 0 deletions solvers/BUILD.bazel
Original file line number Diff line number Diff line change
Expand Up @@ -1326,6 +1326,7 @@ drake_cc_googletest(
":generic_trivial_cost",
":ibex_solver",
":mathematical_program",
"//common/test_utilities:expect_throws_message",
],
)

Expand Down
169 changes: 146 additions & 23 deletions solvers/ibex_solver.cc
Original file line number Diff line number Diff line change
Expand Up @@ -4,6 +4,7 @@
#include <utility>
#include <vector>

#include <fmt/format.h>
#include <ibex.h>

#include "drake/common/text_logging.h"
Expand All @@ -23,6 +24,143 @@ using symbolic::Variable;

namespace {

struct IbexOptions {
// Relative precision on the objective. See
// http://www.ibex-lib.org/doc/optim.html?highlight=eps#objective-precision-criteria
// for details.
double rel_eps_f{ibex::Optimizer::default_rel_eps_f};

// Absolute precision on the objective. See
// http://www.ibex-lib.org/doc/optim.html?highlight=eps#objective-precision-criteria
// for details.
double abs_eps_f{ibex::Optimizer::default_abs_eps_f};

// Equality relaxation value. See
// http://www.ibex-lib.org/doc/optim.html?highlight=eps#the-output-of-ibexopt
// for details.
double eps_h{ibex::NormalizedSystem::default_eps_h};

// Activate rigor mode (certify feasibility of equations). See
// http://www.ibex-lib.org/doc/optim.html?highlight=rigor#return-status for
// details.
bool rigor{false};

// Random seed (useful for reproducibility).
double random_seed{ibex::DefaultOptimizer::default_random_seed};

// Precision on the variable.
double eps_x{ibex::Optimizer::default_eps_x};

// Activate trace. Updates of loup/uplo are printed while minimizing.
// - 0 (by default): nothing is printed.
// - 1: prints every loup/uplo update.
// - 2: also prints each handled node.
int trace{0};

// Timeout (time in seconds). 0.0 indicates +∞.
double timeout{0.0};
};

IbexOptions ParseOptions(const SolverOptions& merged_options) {
IbexOptions options;

for (const auto& it : merged_options.GetOptionsDouble(IbexSolver::id())) {
if (it.first == "rel_eps_f") {
if (it.second <= 0) {
throw std::runtime_error{fmt::format(
"IbexSolver: '{option}' option should have a positive value but "
"'{value}' was provided.",
fmt::arg("option", it.first), fmt::arg("value", it.second))};
}
options.rel_eps_f = it.second;
continue;
}
if (it.first == "abs_eps_f") {
if (it.second <= 0) {
throw std::runtime_error{fmt::format(
"IbexSolver: '{option}' option should have a positive value but "
"'{value}' was provided.",
fmt::arg("option", it.first), fmt::arg("value", it.second))};
}
options.abs_eps_f = it.second;
continue;
}
if (it.first == "eps_h") {
if (it.second <= 0) {
throw std::runtime_error{fmt::format(
"IbexSolver: '{option}' option should have a positive value but "
"'{value}' was provided.",
fmt::arg("option", it.first), fmt::arg("value", it.second))};
}
options.eps_h = it.second;
continue;
}
if (it.first == "random_seed") {
options.random_seed = it.second;
continue;
}
if (it.first == "eps_x") {
if (it.second <= 0) {
throw std::runtime_error{fmt::format(
"IbexSolver: '{option}' option should have a positive value but "
"'{value}' was provided.",
fmt::arg("option", it.first), fmt::arg("value", it.second))};
}
options.eps_x = it.second;
continue;
}
if (it.first == "timeout") {
if (it.second < 0) {
throw std::runtime_error{fmt::format(
"IbexSolver: '{option}' option should have a non-negative value "
"but '{value}' was provided.",
fmt::arg("option", it.first), fmt::arg("value", it.second))};
}
options.timeout = it.second;
continue;
}
throw std::runtime_error{fmt::format(
"IbexSolver: unsupported option '{option}' with double value "
"'{value}'.",
fmt::arg("option", it.first), fmt::arg("value", it.second))};
}

// Handles kPrintToConsole.
if (merged_options.get_print_to_console()) {
options.trace = 1;
}

for (const auto& it : merged_options.GetOptionsInt(IbexSolver::id())) {
if (it.first == "rigor") {
options.rigor = it.second != 0;
continue;
}
if (it.first == "trace") {
const int value{it.second};
if (value < 0 || value > 2) {
throw std::runtime_error{
fmt::format("IbexSolver: cannot set IBEX Solver option 'trace' "
"to value '{value}'. It should be 0, 1, or, 2.",
fmt::arg("value", value))};
}
options.trace = value;
continue;
}
throw std::runtime_error{fmt::format(
"IbexSolver: unsupported option '{option}' with int value '{value}'.",
fmt::arg("option", it.first), fmt::arg("value", it.second))};
}

for (const auto& it : merged_options.GetOptionsStr(IbexSolver::id())) {
throw std::runtime_error{fmt::format(
"IbexSolver: unsupported option '{option}' with string value "
"'{value}'.",
fmt::arg("option", it.first), fmt::arg("value", it.second))};
}

return options;
}

// Adds `f` into `factory` using `ibex_converter` and `expr_ctrs`.
//
// @throw if `f` is non-atomic.
Expand Down Expand Up @@ -56,26 +194,14 @@ VectorXd ExtractMidpoints(const ibex::IntervalVector& iv) {
return v;
}

void DoOptimize(const ibex::System& sys,
void DoOptimize(const ibex::System& sys, const IbexOptions& options,
MathematicalProgramResult* const result) {
// TODO(soonho): Make the followings as solver options.
const double rel_eps_f = ibex::Optimizer::default_rel_eps_f;
const double abs_eps_f = ibex::Optimizer::default_abs_eps_f;
const double eps_h = ibex::NormalizedSystem::default_eps_h;
const bool rigor = false;
const bool in_hc4 = !(sys.nb_ctr > 0 && sys.nb_ctr < sys.f_ctrs.image_dim());
const double random_seed = ibex::DefaultOptimizer::default_random_seed;
const double eps_x = ibex::Optimizer::default_eps_x;
const double timeout = 30.0; /* sec */
// - 0 (by default): nothing is printed
// - 1: prints every loup/uplo update.
// - 2: prints also each handled node
const int trace = 0;

ibex::DefaultOptimizer o(sys, rel_eps_f, abs_eps_f, eps_h, rigor, in_hc4,
random_seed, eps_x);
o.trace = trace;
o.timeout = timeout;
ibex::DefaultOptimizer o(sys, options.rel_eps_f, options.abs_eps_f,
options.eps_h, options.rigor, in_hc4,
options.random_seed, options.eps_x);
o.trace = options.trace;
o.timeout = options.timeout;
const ibex::Optimizer::Status status = o.optimize(sys.box);

switch (status) {
Expand Down Expand Up @@ -143,10 +269,7 @@ void IbexSolver::DoSolve(const MathematicalProgram& prog,
}

unused(initial_guess);
unused(merged_options);

// TODO(soonho): Throw an exception when there are options that we do not
// handle yet.
const IbexOptions options{ParseOptions(merged_options)};

// Creates a converter. Internally, it creates ibex variables.
internal::IbexConverter ibex_converter(prog.decision_variables());
Expand Down Expand Up @@ -242,7 +365,7 @@ void IbexSolver::DoSolve(const MathematicalProgram& prog,
}

ibex::System sys(factory);
DoOptimize(sys, result);
DoOptimize(sys, options, result);
}

} // namespace solvers
Expand Down
18 changes: 16 additions & 2 deletions solvers/ibex_solver.h
Original file line number Diff line number Diff line change
Expand Up @@ -9,7 +9,7 @@
namespace drake {
namespace solvers {
/// An implementation of SolverInterface for the IBEX solver
/// (http://www.ibex-lib.org/)
/// (http://www.ibex-lib.org).
///
/// This solver supports the following constraints / costs:
/// - ExponentialConeConstraint
Expand All @@ -26,7 +26,21 @@ namespace solvers {
/// @note Only costs and constraints that support symbolic evaluation are
/// compatible with this solver.
///
/// TODO(soonho): Add and enumerate supported options here.
/// Currently this implementation supports the following options:
/// - rel_eps_f <double>: Relative precision (∈ ℝ⁺) on the objective.
/// - abs_eps_f <double>: Absolute precision (∈ ℝ⁺) on the objective.
/// - eps_h <double>: Equality relaxation value (∈ ℝ⁺).
/// - rigor <int>: Activate rigor mode (certify feasibility of equations).
/// 0 --> rigor off, != 0 --> rigor on.
/// - random_seed <double>: Random seed (useful for reproducibility).
/// - eps_x <double>: Precision on the variable (∈ ℝ⁺).
/// - trace <int>: Activate trace. Updates of loup/uplo are printed while
/// minimizing. 0 - nothing is printed. 1 - prints every
/// loup/uplo update. 2 - prints also each handled node.
/// Note that trace = 1 if kPrintToConsole = true.
/// - timeout <double>: Timeout (time in seconds). 0.0 indicates +∞.
///
/// See http://www.ibex-lib.org/doc/optim.html#options for more information.
class IbexSolver final : public SolverBase {
public:
DRAKE_NO_COPY_NO_MOVE_NO_ASSIGN(IbexSolver)
Expand Down
6 changes: 6 additions & 0 deletions solvers/solver_options.h
Original file line number Diff line number Diff line change
Expand Up @@ -52,6 +52,12 @@ namespace solvers {
* Note that Drake only supports a subset of the options listed in the
* reference. @see DrealSolver for the subset of these options supported by the
* solver interface.
*
* "IBEX" -- Parameter name and values as specified in IBEX Reference
* http://www.ibex-lib.org/doc/optim.html?highlight=eps#options.
* Note that Drake only supports a subset of the options listed in the
* reference. @see IbexSolver for the subset of these options supported by the
* solver interface.
*/
class SolverOptions {
public:
Expand Down
Loading

0 comments on commit ed39751

Please sign in to comment.