Skip to content

Commit

Permalink
[solvers] Remove uses of SolverType (RobotLocomotion#15214)
Browse files Browse the repository at this point in the history
SolverType was left intact for compatibility reasons; we should not use
it in code that users might imitate.
  • Loading branch information
jwnimmer-tri authored Jun 20, 2021
1 parent 3cd65f5 commit 329d6f4
Show file tree
Hide file tree
Showing 6 changed files with 63 additions and 70 deletions.
2 changes: 2 additions & 0 deletions solvers/solver_type.h
Original file line number Diff line number Diff line change
Expand Up @@ -3,6 +3,8 @@
namespace drake {
namespace solvers {

/** This type only exists for backwards compatiblity, and should not be used in
new code. */
enum class SolverType {
kClp,
kCsdp,
Expand Down
3 changes: 2 additions & 1 deletion solvers/solver_type_converter.h
Original file line number Diff line number Diff line change
Expand Up @@ -9,7 +9,8 @@
namespace drake {
namespace solvers {

/// Converts between SolverType and SolverId.
/// Converts between SolverType and SolverId. This class only exists for
/// backwards compatiblity, and should not be used in new code.
class SolverTypeConverter {
public:
DRAKE_NO_COPY_NO_MOVE_NO_ASSIGN(SolverTypeConverter);
Expand Down
17 changes: 8 additions & 9 deletions solvers/test/linear_program_examples.cc
Original file line number Diff line number Diff line change
Expand Up @@ -5,7 +5,8 @@
#include <gtest/gtest.h>

#include "drake/common/test_utilities/eigen_matrix_compare.h"
#include "drake/solvers/solver_type_converter.h"
#include "drake/solvers/ipopt_solver.h"
#include "drake/solvers/mosek_solver.h"
#include "drake/solvers/test/mathematical_program_test_util.h"

using Eigen::Vector4d;
Expand Down Expand Up @@ -135,7 +136,7 @@ LinearProgram0::LinearProgram0(CostForm cost_form,
void LinearProgram0::CheckSolution(
const MathematicalProgramResult& result) const {
const double tol = GetSolverSolutionDefaultCompareTolerance(
SolverTypeConverter::IdToType(result.get_solver_id()).value());
result.get_solver_id());
EXPECT_TRUE(CompareMatrices(result.GetSolution(x_), x_expected_, tol,
MatrixCompareType::absolute));
ExpectSolutionCostAccurate(*prog(), result, tol);
Expand Down Expand Up @@ -178,7 +179,7 @@ LinearProgram1::LinearProgram1(CostForm cost_form,
void LinearProgram1::CheckSolution(
const MathematicalProgramResult& result) const {
const double tol = GetSolverSolutionDefaultCompareTolerance(
SolverTypeConverter::IdToType(result.get_solver_id()).value());
result.get_solver_id());
EXPECT_TRUE(CompareMatrices(result.GetSolution(x_), x_expected_, tol,
MatrixCompareType::absolute));
ExpectSolutionCostAccurate(*prog(), result, tol);
Expand Down Expand Up @@ -268,7 +269,7 @@ LinearProgram2::LinearProgram2(CostForm cost_form,
void LinearProgram2::CheckSolution(
const MathematicalProgramResult& result) const {
const double tol = GetSolverSolutionDefaultCompareTolerance(
SolverTypeConverter::IdToType(result.get_solver_id()).value());
result.get_solver_id());
EXPECT_TRUE(CompareMatrices(result.GetSolution(x_), x_expected_, tol,
MatrixCompareType::absolute));
ExpectSolutionCostAccurate(*prog(), result, tol);
Expand Down Expand Up @@ -342,15 +343,13 @@ LinearProgram3::LinearProgram3(CostForm cost_form,
void LinearProgram3::CheckSolution(
const MathematicalProgramResult& result) const {
// Mosek has a looser tolerance.
const SolverType solver_type =
SolverTypeConverter::IdToType(result.get_solver_id()).value();
double tol = GetSolverSolutionDefaultCompareTolerance(solver_type);
if (solver_type == SolverType::kMosek) {
double tol = GetSolverSolutionDefaultCompareTolerance(result.get_solver_id());
if (result.get_solver_id() == MosekSolver::id()) {
tol = 1E-6;
}
// Ipopt has a looser objective tolerance
double cost_tol = tol;
if (solver_type == SolverType::kIpopt) {
if (result.get_solver_id() == IpoptSolver::id()) {
cost_tol = 1E-5;
}
EXPECT_TRUE(CompareMatrices(result.GetSolution(x_), x_expected_, tol,
Expand Down
64 changes: 33 additions & 31 deletions solvers/test/optimization_examples.cc
Original file line number Diff line number Diff line change
Expand Up @@ -3,7 +3,14 @@
#include <gtest/gtest.h>

#include "drake/common/test_utilities/eigen_matrix_compare.h"
#include "drake/solvers/solver_type_converter.h"
#include "drake/solvers/clp_solver.h"
#include "drake/solvers/gurobi_solver.h"
#include "drake/solvers/ipopt_solver.h"
#include "drake/solvers/mosek_solver.h"
#include "drake/solvers/nlopt_solver.h"
#include "drake/solvers/osqp_solver.h"
#include "drake/solvers/scs_solver.h"
#include "drake/solvers/snopt_solver.h"
#include "drake/solvers/test/mathematical_program_test_util.h"

using Eigen::Matrix2d;
Expand Down Expand Up @@ -72,42 +79,37 @@ void OptimizationProgram::RunProblem(SolverInterface* solver) {
EXPECT_EQ(solver->ExplainUnsatisfiedProgramAttributes(*prog_), "");
const MathematicalProgramResult result =
RunSolver(*prog_, *solver, initial_guess());
const std::optional<SolverType> solver_type =
SolverTypeConverter::IdToType(result.get_solver_id());
ASSERT_TRUE(solver_type != std::nullopt);
CheckSolution(result);
}
}

double OptimizationProgram::GetSolverSolutionDefaultCompareTolerance(
SolverType solver_type) const {
switch (solver_type) {
case SolverType::kClp: {
return 1E-8;
}
case SolverType::kMosek: {
return 1E-10;
}
case SolverType::kGurobi: {
return 1E-10;
}
case SolverType::kSnopt: {
return 1E-8;
}
case SolverType::kIpopt: {
return 1E-6;
}
case SolverType::kNlopt: {
return 1E-6;
}
case SolverType::kOsqp: {
return 1E-10;
}
case SolverType::kScs: {
return 3E-5; // Scs is not very accurate.
}
default: { throw std::runtime_error("Unsupported solver type."); }
SolverId solver_id) const {
if (solver_id == ClpSolver::id()) {
return 1E-8;
}
if (solver_id == MosekSolver::id()) {
return 1E-10;
}
if (solver_id == GurobiSolver::id()) {
return 1E-10;
}
if (solver_id == SnoptSolver::id()) {
return 1E-8;
}
if (solver_id == IpoptSolver::id()) {
return 1E-6;
}
if (solver_id == NloptSolver::id()) {
return 1E-6;
}
if (solver_id == OsqpSolver::id()) {
return 1E-10;
}
if (solver_id == ScsSolver::id()) {
return 3E-5; // Scs is not very accurate.
}
throw std::runtime_error("Unsupported solver type.");
}

LinearSystemExample1::LinearSystemExample1()
Expand Down
2 changes: 1 addition & 1 deletion solvers/test/optimization_examples.h
Original file line number Diff line number Diff line change
Expand Up @@ -54,7 +54,7 @@ class OptimizationProgram {

virtual void CheckSolution(const MathematicalProgramResult& result) const = 0;

double GetSolverSolutionDefaultCompareTolerance(SolverType solver_type) const;
double GetSolverSolutionDefaultCompareTolerance(SolverId solver_id) const;

void RunProblem(SolverInterface* solver);

Expand Down
45 changes: 17 additions & 28 deletions solvers/test/quadratic_program_examples.cc
Original file line number Diff line number Diff line change
Expand Up @@ -8,9 +8,10 @@
#include <gtest/gtest.h>

#include "drake/common/test_utilities/eigen_matrix_compare.h"
#include "drake/solvers/clp_solver.h"
#include "drake/solvers/gurobi_solver.h"
#include "drake/solvers/mosek_solver.h"
#include "drake/solvers/snopt_solver.h"
#include "drake/solvers/solver_type_converter.h"
#include "drake/solvers/test/mathematical_program_test_util.h"

using Eigen::Vector4d;
Expand Down Expand Up @@ -122,12 +123,10 @@ QuadraticProgram0::QuadraticProgram0(CostForm cost_form,

void QuadraticProgram0::CheckSolution(
const MathematicalProgramResult& result) const {
const SolverType solver_type =
SolverTypeConverter::IdToType(result.get_solver_id()).value();
double tol = GetSolverSolutionDefaultCompareTolerance(solver_type);
if (solver_type == SolverType::kGurobi) {
double tol = GetSolverSolutionDefaultCompareTolerance(result.get_solver_id());
if (result.get_solver_id() == GurobiSolver::id()) {
tol = 1E-8;
} else if (solver_type == SolverType::kMosek) {
} else if (result.get_solver_id() == MosekSolver::id()) {
// TODO(hongkai.dai): the default parameter in Mosek 8 generates low
// accuracy solution. We should set the accuracy tolerance
// MSK_DPARAM_INTPNT_QO_REL_TOL_GAP to 1E-10 to improve the accuracy.
Expand Down Expand Up @@ -213,12 +212,10 @@ QuadraticProgram1::QuadraticProgram1(CostForm cost_form,

void QuadraticProgram1::CheckSolution(
const MathematicalProgramResult& result) const {
const SolverType solver_type =
SolverTypeConverter::IdToType(result.get_solver_id()).value();
double tol = GetSolverSolutionDefaultCompareTolerance(solver_type);
if (solver_type == SolverType::kGurobi) {
double tol = GetSolverSolutionDefaultCompareTolerance(result.get_solver_id());
if (result.get_solver_id() == GurobiSolver::id()) {
tol = 1E-8;
} else if (solver_type == SolverType::kMosek) {
} else if (result.get_solver_id() == MosekSolver::id()) {
tol = 1E-7;
}
EXPECT_TRUE(CompareMatrices(result.GetSolution(x_), x_expected_, tol,
Expand Down Expand Up @@ -256,14 +253,12 @@ QuadraticProgram2::QuadraticProgram2(CostForm cost_form,

void QuadraticProgram2::CheckSolution(
const MathematicalProgramResult& result) const {
const SolverType solver_type =
SolverTypeConverter::IdToType(result.get_solver_id()).value();
double tol = GetSolverSolutionDefaultCompareTolerance(solver_type);
if (solver_type == SolverType::kMosek) {
double tol = GetSolverSolutionDefaultCompareTolerance(result.get_solver_id());
if (result.get_solver_id() == MosekSolver::id()) {
tol = 1E-8;
} else if (solver_type == SolverType::kSnopt) {
} else if (result.get_solver_id() == SnoptSolver::id()) {
tol = 1E-6;
} else if (solver_type == SolverType::kClp) {
} else if (result.get_solver_id() == ClpSolver::id()) {
tol = 2E-8;
}
EXPECT_TRUE(CompareMatrices(result.GetSolution(x_), x_expected_, tol,
Expand Down Expand Up @@ -319,10 +314,8 @@ QuadraticProgram3::QuadraticProgram3(CostForm cost_form,

void QuadraticProgram3::CheckSolution(
const MathematicalProgramResult& result) const {
const SolverType solver_type =
SolverTypeConverter::IdToType(result.get_solver_id()).value();
double tol = GetSolverSolutionDefaultCompareTolerance(solver_type);
if (solver_type == SolverType::kMosek) {
double tol = GetSolverSolutionDefaultCompareTolerance(result.get_solver_id());
if (result.get_solver_id() == MosekSolver::id()) {
tol = 1E-8;
}
EXPECT_TRUE(CompareMatrices(result.GetSolution(x_), x_expected_, tol,
Expand Down Expand Up @@ -374,10 +367,8 @@ QuadraticProgram4::QuadraticProgram4(CostForm cost_form,

void QuadraticProgram4::CheckSolution(
const MathematicalProgramResult& result) const {
const SolverType solver_type =
SolverTypeConverter::IdToType(result.get_solver_id()).value();
double tol = GetSolverSolutionDefaultCompareTolerance(solver_type);
if (solver_type == SolverType::kMosek) {
double tol = GetSolverSolutionDefaultCompareTolerance(result.get_solver_id());
if (result.get_solver_id() == MosekSolver::id()) {
tol = 1E-8;
}
EXPECT_TRUE(CompareMatrices(result.GetSolution(x_), x_expected_, tol,
Expand Down Expand Up @@ -434,10 +425,8 @@ void TestQPonUnitBallExample(const SolverInterface& solver) {
RunSolver(prog, solver, initial_guess);
const auto& x_value = result.GetSolution(x);

const SolverType solver_type =
SolverTypeConverter::IdToType(result.get_solver_id()).value();
double tol = 1E-4;
if (solver_type == SolverType::kMosek) {
if (result.get_solver_id() == MosekSolver::id()) {
// Regression from MOSEK 8.1 to MOSEK 9.2.
tol = 2E-4;
}
Expand Down

0 comments on commit 329d6f4

Please sign in to comment.