diff --git a/bindings/pydrake/solvers/BUILD.bazel b/bindings/pydrake/solvers/BUILD.bazel index 30cfc9dc7e9e..bb288c3cfad7 100644 --- a/bindings/pydrake/solvers/BUILD.bazel +++ b/bindings/pydrake/solvers/BUILD.bazel @@ -46,6 +46,7 @@ drake_pybind_library( "//bindings/pydrake:symbolic_types_pybind", "//bindings/pydrake/common:cpp_param_pybind", "//bindings/pydrake/common:cpp_template_pybind", + "//bindings/pydrake/common:deprecation_pybind", "//bindings/pydrake/common:eigen_pybind", "//bindings/pydrake/common:value_pybind", ], @@ -173,7 +174,7 @@ drake_py_unittest( }), deps = [ ":solvers", - "//bindings/pydrake/common/test_utilities:numpy_compare_py", + "//bindings/pydrake/common/test_utilities", ], ) diff --git a/bindings/pydrake/solvers/solvers_py_dreal.cc b/bindings/pydrake/solvers/solvers_py_dreal.cc index 8cd42dd2e748..47c8536cd89b 100644 --- a/bindings/pydrake/solvers/solvers_py_dreal.cc +++ b/bindings/pydrake/solvers/solvers_py_dreal.cc @@ -2,6 +2,7 @@ #include "pybind11/pybind11.h" #include "pybind11/stl.h" +#include "drake/bindings/pydrake/common/deprecation_pybind.h" #include "drake/bindings/pydrake/documentation_pybind.h" #include "drake/bindings/pydrake/pydrake_pybind.h" #include "drake/bindings/pydrake/solvers/solvers_py.h" @@ -11,21 +12,26 @@ namespace drake { namespace pydrake { namespace internal { +#pragma GCC diagnostic push +#pragma GCC diagnostic ignored "-Wdeprecated-declarations" void DefineSolversDreal(py::module m) { // NOLINTNEXTLINE(build/namespaces): Emulate placement in namespace. using namespace drake::solvers; constexpr auto& doc = pydrake_doc.drake.solvers; auto solver = py::class_( - m, "DrealSolver", doc.DrealSolver.doc) - .def_static("id", &DrealSolver::id, doc.DrealSolver.id.doc); + m, "DrealSolver", doc.DrealSolver.doc_deprecated) + .def_static("id", + WrapDeprecated(doc.DrealSolver.id.doc_deprecated, + &DrealSolver::id), + doc.DrealSolver.id.doc_deprecated); { using Class = DrealSolver::Interval; const auto& cls_doc = doc.DrealSolver.Interval; - py::class_(solver, "Interval", cls_doc.doc) - .def(py::init(), py::arg("low"), py::arg("high"), - cls_doc.ctor.doc) + py::class_(solver, "Interval", cls_doc.doc_deprecated) + .def(py_init_deprecated(cls_doc.doc_deprecated), + py::arg("low"), py::arg("high"), cls_doc.doc_deprecated) .def("diam", &Class::diam, cls_doc.diam.doc) .def("mid", &Class::mid, cls_doc.mid.doc) .def("low", &Class::low, cls_doc.low.doc) @@ -40,14 +46,22 @@ void DefineSolversDreal(py::module m) { .value("kNotUse", Class::kNotUse, cls_doc.kNotUse.doc); } - solver.def(py::init<>(), doc.DrealSolver.ctor.doc) - .def_static("CheckSatisfiability", &DrealSolver::CheckSatisfiability, + solver + .def(py_init_deprecated(doc.DrealSolver.ctor.doc_deprecated), + doc.DrealSolver.ctor.doc_deprecated) + .def_static("CheckSatisfiability", + WrapDeprecated(doc.DrealSolver.CheckSatisfiability.doc_deprecated, + &DrealSolver::CheckSatisfiability), py::arg("f"), py::arg("delta"), - doc.DrealSolver.CheckSatisfiability.doc) - .def_static("Minimize", &DrealSolver::Minimize, py::arg("objective"), - py::arg("constraint"), py::arg("delta"), - py::arg("local_optimization"), doc.DrealSolver.Minimize.doc); + doc.DrealSolver.CheckSatisfiability.doc_deprecated) + .def_static("Minimize", + WrapDeprecated( + doc.DrealSolver.Minimize.doc_deprecated, &DrealSolver::Minimize), + py::arg("objective"), py::arg("constraint"), py::arg("delta"), + py::arg("local_optimization"), + doc.DrealSolver.Minimize.doc_deprecated); } +#pragma GCC diagnostic pop } // namespace internal } // namespace pydrake diff --git a/bindings/pydrake/solvers/solvers_py_ibex.cc b/bindings/pydrake/solvers/solvers_py_ibex.cc index da4c99618acf..32a069b61637 100644 --- a/bindings/pydrake/solvers/solvers_py_ibex.cc +++ b/bindings/pydrake/solvers/solvers_py_ibex.cc @@ -1,6 +1,7 @@ #include "pybind11/eigen.h" #include "pybind11/pybind11.h" +#include "drake/bindings/pydrake/common/deprecation_pybind.h" #include "drake/bindings/pydrake/documentation_pybind.h" #include "drake/bindings/pydrake/pydrake_pybind.h" #include "drake/bindings/pydrake/solvers/solvers_py.h" @@ -10,15 +11,22 @@ namespace drake { namespace pydrake { namespace internal { +#pragma GCC diagnostic push +#pragma GCC diagnostic ignored "-Wdeprecated-declarations" void DefineSolversIbex(py::module m) { // NOLINTNEXTLINE(build/namespaces): Emulate placement in namespace. using namespace drake::solvers; constexpr auto& doc = pydrake_doc.drake.solvers; - py::class_(m, "IbexSolver", doc.IbexSolver.doc) - .def(py::init<>(), doc.IbexSolver.ctor.doc) - .def_static("id", &IbexSolver::id, doc.IbexSolver.id.doc); + py::class_( + m, "IbexSolver", doc.IbexSolver.doc_deprecated) + .def(py_init_deprecated(doc.IbexSolver.ctor.doc_deprecated), + doc.IbexSolver.ctor.doc_deprecated) + .def_static("id", + WrapDeprecated(doc.IbexSolver.id.doc_deprecated, &IbexSolver::id), + doc.IbexSolver.id.doc_deprecated); } +#pragma GCC diagnostic pop } // namespace internal } // namespace pydrake diff --git a/bindings/pydrake/solvers/solvers_py_mathematicalprogram.cc b/bindings/pydrake/solvers/solvers_py_mathematicalprogram.cc index c582c448ca6a..49a3f0e05fb2 100644 --- a/bindings/pydrake/solvers/solvers_py_mathematicalprogram.cc +++ b/bindings/pydrake/solvers/solvers_py_mathematicalprogram.cc @@ -458,14 +458,13 @@ void BindSolverInterfaceAndFlags(py::module m) { .value("kLCP", ProgramType::kLCP, doc.ProgramType.kLCP.doc) .value("kUnknown", ProgramType::kUnknown, doc.ProgramType.kUnknown.doc); - py::enum_(m, "SolverType", doc.SolverType.doc) + py::enum_ solver_type(m, "SolverType", doc.SolverType.doc); + solver_type // BR .value("kClp", SolverType::kClp, doc.SolverType.kClp.doc) .value("kCsdp", SolverType::kCsdp, doc.SolverType.kCsdp.doc) - .value("kDReal", SolverType::kDReal, doc.SolverType.kDReal.doc) .value("kEqualityConstrainedQP", SolverType::kEqualityConstrainedQP, doc.SolverType.kEqualityConstrainedQP.doc) .value("kGurobi", SolverType::kGurobi, doc.SolverType.kGurobi.doc) - .value("kIbex", SolverType::kIbex, doc.SolverType.kIbex.doc) .value("kIpopt", SolverType::kIpopt, doc.SolverType.kIpopt.doc) .value("kLinearSystem", SolverType::kLinearSystem, doc.SolverType.kLinearSystem.doc) @@ -476,6 +475,13 @@ void BindSolverInterfaceAndFlags(py::module m) { .value("kScs", SolverType::kScs, doc.SolverType.kScs.doc) .value("kSnopt", SolverType::kSnopt, doc.SolverType.kSnopt.doc); +#pragma GCC diagnostic push +#pragma GCC diagnostic ignored "-Wdeprecated-declarations" + solver_type // BR + .value("kDReal", SolverType::kDReal, "(Deprecated.)") + .value("kIbex", SolverType::kIbex, "(Deprecated.)"); +#pragma GCC diagnostic pop + // TODO(jwnimmer-tri) Bind the accessors for SolverOptions. py::class_(m, "SolverOptions", doc.SolverOptions.doc) .def(py::init<>(), doc.SolverOptions.ctor.doc) diff --git a/bindings/pydrake/solvers/test/dreal_solver_test.py b/bindings/pydrake/solvers/test/dreal_solver_test.py index acf3f0259f25..971a1c0c9e25 100644 --- a/bindings/pydrake/solvers/test/dreal_solver_test.py +++ b/bindings/pydrake/solvers/test/dreal_solver_test.py @@ -4,6 +4,7 @@ import numpy as np from pydrake.common.containers import EqualToDict +from pydrake.common.test_utilities.deprecation import catch_drake_warnings from pydrake.solvers import mathematicalprogram as mp from pydrake.solvers.dreal import DrealSolver from pydrake.symbolic import Variable, logical_and, logical_or @@ -15,8 +16,11 @@ def test_dreal_solver(self): prog = mp.MathematicalProgram() x = prog.NewContinuousVariables(1, "x") prog.AddBoundingBoxConstraint(-1, 1, x) - solver = DrealSolver() - self.assertEqual(solver.solver_id(), DrealSolver.id()) + with catch_drake_warnings(expected_count=1): + solver = DrealSolver() + with catch_drake_warnings(expected_count=1): + dreal_id = DrealSolver.id() + self.assertEqual(solver.solver_id(), dreal_id) self.assertTrue(solver.available()) self.assertEqual(solver.solver_id().name(), "dReal") self.assertEqual(solver.SolverName(), "dReal") @@ -25,7 +29,8 @@ def test_dreal_solver(self): self.assertTrue(result.is_success()) def test_interval(self): - interval = DrealSolver.Interval(low=3.0, high=4.0) + with catch_drake_warnings(expected_count=1): + interval = DrealSolver.Interval(low=3.0, high=4.0) self.assertEqual(interval.low(), 3.0) self.assertEqual(interval.high(), 4.0) self.assertEqual(interval.diam(), 1.0) @@ -34,8 +39,9 @@ def test_interval(self): def test_dreal_satisfiability(self): x = Variable("x") f = logical_and(x > 1, x < 2) - interval_box = EqualToDict( - DrealSolver.CheckSatisfiability(f=f, delta=0.01)) + with catch_drake_warnings(expected_count=1): + interval_box = EqualToDict( + DrealSolver.CheckSatisfiability(f=f, delta=0.01)) self.assertEqual(len(interval_box), 1) self.assertIsInstance(interval_box[x], DrealSolver.Interval) @@ -47,12 +53,13 @@ def test_local_optimization(self): def test_minimize(self): x = Variable("x") delta = 0.01 - interval_box = EqualToDict( - DrealSolver.Minimize( - objective=x**2, - constraint=logical_and(x >= 1, x <= 10), - delta=delta, - local_optimization=DrealSolver.LocalOptimization.kUse)) + with catch_drake_warnings(expected_count=1): + interval_box = EqualToDict( + DrealSolver.Minimize( + objective=x**2, + constraint=logical_and(x >= 1, x <= 10), + delta=delta, + local_optimization=DrealSolver.LocalOptimization.kUse)) self.assertEqual(len(interval_box), 1) self.assertIsInstance(interval_box[x], DrealSolver.Interval) print(interval_box[x].diam()) @@ -60,5 +67,6 @@ def test_minimize(self): def unavailable(self): """Per the BUILD file, this test is only run when dReal is disabled.""" - solver = DrealSolver() + with catch_drake_warnings(expected_count=1): + solver = DrealSolver() self.assertFalse(solver.available()) diff --git a/bindings/pydrake/solvers/test/ibex_solver_test.py b/bindings/pydrake/solvers/test/ibex_solver_test.py index 759b513e8306..083681bbe109 100644 --- a/bindings/pydrake/solvers/test/ibex_solver_test.py +++ b/bindings/pydrake/solvers/test/ibex_solver_test.py @@ -3,6 +3,7 @@ import numpy as np from pydrake.common.test_utilities import numpy_compare +from pydrake.common.test_utilities.deprecation import catch_drake_warnings from pydrake.solvers import mathematicalprogram as mp from pydrake.solvers.ibex import IbexSolver @@ -14,8 +15,11 @@ def test_ibex_solver(self): prog.AddBoundingBoxConstraint(-1., 1., x[0]) prog.AddBoundingBoxConstraint(-1., 1., x[1]) prog.AddCost(x[0] - x[1]) - solver = IbexSolver() - self.assertEqual(solver.solver_id(), IbexSolver.id()) + with catch_drake_warnings(expected_count=1): + solver = IbexSolver() + with catch_drake_warnings(expected_count=1): + ibex_id = IbexSolver.id() + self.assertEqual(solver.solver_id(), ibex_id) self.assertTrue(solver.available()) self.assertEqual(solver.solver_id().name(), "IBEX") @@ -29,5 +33,6 @@ def test_ibex_solver(self): def unavailable(self): """Per the BUILD file, this test is only run when Ibex is disabled.""" - solver = IbexSolver() + with catch_drake_warnings(expected_count=1): + solver = IbexSolver() self.assertFalse(solver.available()) diff --git a/solvers/BUILD.bazel b/solvers/BUILD.bazel index 7040e1d96316..5b48947b207b 100644 --- a/solvers/BUILD.bazel +++ b/solvers/BUILD.bazel @@ -1294,6 +1294,7 @@ drake_cc_googletest( drake_cc_googletest( name = "dreal_solver_test", timeout = "moderate", + copts = ["-Wno-deprecated-declarations"], # For most of floating-point operations, Valgrind core only supports the # IEEE default mode (round to nearest) while dReal uses to +infinity # and to -infinity rounding modes intensively to maintain conservative @@ -1348,6 +1349,7 @@ drake_cc_googletest( drake_cc_googletest( name = "ibex_solver_test", + copts = ["-Wno-deprecated-declarations"], deps = [ ":generic_trivial_constraint", ":generic_trivial_cost", diff --git a/solvers/dreal_solver.cc b/solvers/dreal_solver.cc index f0fb52098f2c..e7f1a984e538 100644 --- a/solvers/dreal_solver.cc +++ b/solvers/dreal_solver.cc @@ -16,6 +16,9 @@ #include "drake/common/text_logging.h" #include "drake/solvers/mathematical_program.h" +#pragma GCC diagnostic push +#pragma GCC diagnostic ignored "-Wdeprecated-declarations" + namespace drake { namespace solvers { @@ -603,3 +606,5 @@ void DrealSolver::DoSolve( } // namespace solvers } // namespace drake + +#pragma GCC diagnostic pop diff --git a/solvers/dreal_solver.h b/solvers/dreal_solver.h index 2d578fcc4a6d..e478579689a1 100644 --- a/solvers/dreal_solver.h +++ b/solvers/dreal_solver.h @@ -5,6 +5,7 @@ #include #include "drake/common/drake_copyable.h" +#include "drake/common/drake_deprecated.h" #include "drake/common/hash.h" #include "drake/common/symbolic/expression.h" #include "drake/solvers/solver_base.h" @@ -12,28 +13,26 @@ namespace drake { namespace solvers { +/// (Deprecated.) dReal support is being withdrawn from Drake; for details, see +/// https://github.com/RobotLocomotion/drake/pull/18156. This class will be +/// removed from Drake on or after 2023-02-01. +/// /// An implementation of SolverInterface for the dReal4 solver /// (https://github.com/dreal/dreal4). -/// -/// Currently this implementation supports the following options: -/// * precision : This value is used as a termination condition. When -/// the ICP algorithm finds an interval box whose width -/// is smaller than this value, it concludes that the -/// query is delta-satisfiable and provides the interval -/// box as a witness. Default value = 0.001. -/// -/// * use_local_optimization : Use local-optimization algorithms in -/// solving exists-forall problem. For now, -/// the solver is using NLopt. See -/// https://link.springer.com/chapter/10.1007%2F978-3-319-96142-2_15 -/// for details. Default value = True. -/// -/// To see the full list of dReal4 options, visit -/// https://github.com/dreal/dreal4#command-line-options. -class DrealSolver final : public SolverBase { +class DRAKE_DEPRECATED("2023-02-01", + "dReal support is being withdrawn from Drake; for details, see " + "https://github.com/RobotLocomotion/drake/pull/18156") +DrealSolver final : public SolverBase { public: + /// (Deprecated.) dReal support is being withdrawn from Drake; for details, + /// see https://github.com/RobotLocomotion/drake/pull/18156. This class will + /// be removed from Drake on or after 2023-02-01. + /// /// Class representing an interval of doubles. - class Interval { + class DRAKE_DEPRECATED("2023-02-01", + "dReal support is being withdrawn from Drake; for details, see " + "https://github.com/RobotLocomotion/drake/pull/18156") + Interval { public: DRAKE_DEFAULT_COPY_AND_MOVE_AND_ASSIGN(Interval) @@ -62,9 +61,17 @@ class DrealSolver final : public SolverBase { double high_{}; }; +#pragma GCC diagnostic push +#pragma GCC diagnostic ignored "-Wdeprecated-declarations" + /// (Deprecated.) dReal support is being withdrawn from Drake; for details, + /// see https://github.com/RobotLocomotion/drake/pull/18156. This class will + /// be removed from Drake on or after 2023-02-01. using IntervalBox = std::unordered_map; +#pragma GCC diagnostic pop - /// Indicates whether to use dReal's --local-optimization option or not. + /// (Deprecated.) dReal support is being withdrawn from Drake; for details, + /// see https://github.com/RobotLocomotion/drake/pull/18156. This class will + /// be removed from Drake on or after 2023-02-01. enum class LocalOptimization { kUse, ///< Use "--local-optimization" option. kNotUse, ///< Do not use "--local-optimization" option. @@ -72,28 +79,23 @@ class DrealSolver final : public SolverBase { DRAKE_NO_COPY_NO_MOVE_NO_ASSIGN(DrealSolver) + DRAKE_DEPRECATED("2023-02-01", + "dReal support is being withdrawn from Drake; for details, see " + "https://github.com/RobotLocomotion/drake/pull/18156") DrealSolver(); + ~DrealSolver() final; - /// Checks the satisfiability of a given formula @p f with a given precision - /// @p delta. - /// - /// @returns a model, a mapping from a variable to an interval, if @p f is - /// δ-satisfiable. - /// @returns a nullopt, if @p is unsatisfiable. + DRAKE_DEPRECATED("2023-02-01", + "dReal support is being withdrawn from Drake; for details, see " + "https://github.com/RobotLocomotion/drake/pull/18156") static std::optional CheckSatisfiability( const symbolic::Formula& f, double delta); - /// Finds a solution to minimize @p objective function while satisfying a - /// given @p constraint using @p delta. When @p local_optimization is - /// Localoptimization::kUse, enable "--local-optimization" dReal option which - /// uses NLopt's local-optimization algorithms to refine counterexamples in - /// the process of global optimization. - /// - /// @returns a model, a mapping from a variable to an interval, if a solution - /// exists. - /// @returns nullopt, if there is no solution. + DRAKE_DEPRECATED("2023-02-01", + "dReal support is being withdrawn from Drake; for details, see " + "https://github.com/RobotLocomotion/drake/pull/18156") static std::optional Minimize( const symbolic::Expression& objective, const symbolic::Formula& constraint, @@ -102,9 +104,21 @@ class DrealSolver final : public SolverBase { /// @name Static versions of the instance methods with similar names. //@{ + DRAKE_DEPRECATED("2023-02-01", + "dReal support is being withdrawn from Drake; for details, see " + "https://github.com/RobotLocomotion/drake/pull/18156") static SolverId id(); + DRAKE_DEPRECATED("2023-02-01", + "dReal support is being withdrawn from Drake; for details, see " + "https://github.com/RobotLocomotion/drake/pull/18156") static bool is_available(); + DRAKE_DEPRECATED("2023-02-01", + "dReal support is being withdrawn from Drake; for details, see " + "https://github.com/RobotLocomotion/drake/pull/18156") static bool is_enabled(); + DRAKE_DEPRECATED("2023-02-01", + "dReal support is being withdrawn from Drake; for details, see " + "https://github.com/RobotLocomotion/drake/pull/18156") static bool ProgramAttributesSatisfied(const MathematicalProgram&); //@} diff --git a/solvers/dreal_solver_common.cc b/solvers/dreal_solver_common.cc index 0bdd586f8643..703783204965 100644 --- a/solvers/dreal_solver_common.cc +++ b/solvers/dreal_solver_common.cc @@ -8,6 +8,9 @@ // This file contains implementations that are common to both the available and // unavailable flavor of this class. +#pragma GCC diagnostic push +#pragma GCC diagnostic ignored "-Wdeprecated-declarations" + namespace drake { namespace solvers { @@ -41,3 +44,5 @@ bool DrealSolver::ProgramAttributesSatisfied(const MathematicalProgram& prog) { } // namespace solvers } // namespace drake + +#pragma GCC diagnostic pop diff --git a/solvers/ibex_solver.cc b/solvers/ibex_solver.cc index 1d1a4e632cf9..d3c9b7cc4075 100644 --- a/solvers/ibex_solver.cc +++ b/solvers/ibex_solver.cc @@ -10,6 +10,9 @@ #include "drake/common/text_logging.h" #include "drake/solvers/ibex_converter.h" +#pragma GCC diagnostic push +#pragma GCC diagnostic ignored "-Wdeprecated-declarations" + namespace drake { namespace solvers { @@ -373,3 +376,5 @@ void IbexSolver::DoSolve(const MathematicalProgram& prog, } // namespace solvers } // namespace drake + +#pragma GCC diagnostic pop diff --git a/solvers/ibex_solver.h b/solvers/ibex_solver.h index 7e532685f65f..20b5bbc5e757 100644 --- a/solvers/ibex_solver.h +++ b/solvers/ibex_solver.h @@ -1,6 +1,7 @@ #pragma once #include "drake/common/drake_copyable.h" +#include "drake/common/drake_deprecated.h" #include "drake/solvers/mathematical_program.h" #include "drake/solvers/mathematical_program_result.h" #include "drake/solvers/solver_base.h" @@ -8,6 +9,10 @@ namespace drake { namespace solvers { +/// (Deprecated.) IBEX support is being withdrawn from Drake; for details, see +/// https://github.com/RobotLocomotion/drake/pull/18156. This class will be +/// removed from Drake on or after 2023-02-01. +/// /// An implementation of SolverInterface for the IBEX solver /// (http://www.ibex-lib.org). /// @@ -41,11 +46,18 @@ namespace solvers { /// - timeout : 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 { +class DRAKE_DEPRECATED("2023-02-01", + "IBEX support is being withdrawn from Drake; for details, see " + "https://github.com/RobotLocomotion/drake/pull/18156") +IbexSolver final : public SolverBase { public: DRAKE_NO_COPY_NO_MOVE_NO_ASSIGN(IbexSolver) + DRAKE_DEPRECATED("2023-02-01", + "IBEX support is being withdrawn from Drake; for details, see " + "https://github.com/RobotLocomotion/drake/pull/18156") IbexSolver(); + ~IbexSolver() final; // A using-declaration adds these methods into our class's Doxygen. @@ -53,9 +65,21 @@ class IbexSolver final : public SolverBase { /// @name Static versions of the instance methods with similar names. //@{ + DRAKE_DEPRECATED("2023-02-01", + "IBEX support is being withdrawn from Drake; for details, see " + "https://github.com/RobotLocomotion/drake/pull/18156") static SolverId id(); + DRAKE_DEPRECATED("2023-02-01", + "IBEX support is being withdrawn from Drake; for details, see " + "https://github.com/RobotLocomotion/drake/pull/18156") static bool is_available(); + DRAKE_DEPRECATED("2023-02-01", + "IBEX support is being withdrawn from Drake; for details, see " + "https://github.com/RobotLocomotion/drake/pull/18156") static bool is_enabled(); + DRAKE_DEPRECATED("2023-02-01", + "IBEX support is being withdrawn from Drake; for details, see " + "https://github.com/RobotLocomotion/drake/pull/18156") static bool ProgramAttributesSatisfied(const MathematicalProgram&); //@} diff --git a/solvers/ibex_solver_common.cc b/solvers/ibex_solver_common.cc index 13dad66d08f6..5135b96364b3 100644 --- a/solvers/ibex_solver_common.cc +++ b/solvers/ibex_solver_common.cc @@ -8,6 +8,9 @@ // This file contains implementations that are common to both the available and // unavailable flavor of this class. +#pragma GCC diagnostic push +#pragma GCC diagnostic ignored "-Wdeprecated-declarations" + namespace drake { namespace solvers { @@ -45,3 +48,5 @@ bool IbexSolver::ProgramAttributesSatisfied(const MathematicalProgram& prog) { } // namespace solvers } // namespace drake + +#pragma GCC diagnostic pop diff --git a/solvers/solver_type.h b/solvers/solver_type.h index 9c0ca86c2444..f89602af415b 100644 --- a/solvers/solver_type.h +++ b/solvers/solver_type.h @@ -8,10 +8,8 @@ new code. */ enum class SolverType { kClp, kCsdp, - kDReal, kEqualityConstrainedQP, kGurobi, - kIbex, kIpopt, kLinearSystem, kMobyLCP, @@ -21,6 +19,8 @@ enum class SolverType { kSnopt, kScs, kUnrevisedLemke + , kDReal [[deprecated("DRAKE DEPRECATED: dReal support is being withdrawn from Drake; for details, see https://github.com/RobotLocomotion/drake/pull/18156. The deprecated code will be removed from Drake on or after 2023-02-01")]] // NOLINT + , kIbex [[deprecated("DRAKE DEPRECATED: IBEX support is being withdrawn from Drake; for details, see https://github.com/RobotLocomotion/drake/pull/18156. The deprecated code will be removed from Drake on or after 2023-02-01")]] // NOLINT }; } // namespace solvers diff --git a/solvers/solver_type_converter.cc b/solvers/solver_type_converter.cc index 20b54bad0c5f..fd038bfb3dab 100644 --- a/solvers/solver_type_converter.cc +++ b/solvers/solver_type_converter.cc @@ -26,14 +26,10 @@ SolverId SolverTypeConverter::TypeToId(SolverType solver_type) { return ClpSolver::id(); case SolverType::kCsdp: return CsdpSolver::id(); - case SolverType::kDReal: - return DrealSolver::id(); case SolverType::kEqualityConstrainedQP: return EqualityConstrainedQPSolver::id(); case SolverType::kGurobi: return GurobiSolver::id(); - case SolverType::kIbex: - return IbexSolver::id(); case SolverType::kIpopt: return IpoptSolver::id(); case SolverType::kLinearSystem: @@ -52,6 +48,13 @@ SolverId SolverTypeConverter::TypeToId(SolverType solver_type) { return ScsSolver::id(); case SolverType::kUnrevisedLemke: return UnrevisedLemkeSolverId::id(); +#pragma GCC diagnostic push +#pragma GCC diagnostic ignored "-Wdeprecated-declarations" + case SolverType::kDReal: + return DrealSolver::id(); + case SolverType::kIbex: + return IbexSolver::id(); +#pragma GCC diagnostic pop } DRAKE_UNREACHABLE(); } @@ -61,14 +64,10 @@ std::optional SolverTypeConverter::IdToType(SolverId solver_id) { return SolverType::kClp; } else if (solver_id == CsdpSolver::id()) { return SolverType::kCsdp; - } else if (solver_id == DrealSolver::id()) { - return SolverType::kDReal; } else if (solver_id == EqualityConstrainedQPSolver::id()) { return SolverType::kEqualityConstrainedQP; } else if (solver_id == GurobiSolver::id()) { return SolverType::kGurobi; - } else if (solver_id == IbexSolver::id()) { - return SolverType::kIbex; } else if (solver_id == IpoptSolver::id()) { return SolverType::kIpopt; } else if (solver_id == LinearSystemSolver::id()) { @@ -87,6 +86,13 @@ std::optional SolverTypeConverter::IdToType(SolverId solver_id) { return SolverType::kScs; } else if (solver_id == UnrevisedLemkeSolverId::id()) { return SolverType::kUnrevisedLemke; +#pragma GCC diagnostic push +#pragma GCC diagnostic ignored "-Wdeprecated-declarations" + } else if (solver_id == DrealSolver::id()) { + return SolverType::kDReal; + } else if (solver_id == IbexSolver::id()) { + return SolverType::kIbex; +#pragma GCC diagnostic pop } else { return std::nullopt; } diff --git a/solvers/test/solver_type_converter_test.cc b/solvers/test/solver_type_converter_test.cc index c74c2e769705..86b9ccf9c064 100644 --- a/solvers/test/solver_type_converter_test.cc +++ b/solvers/test/solver_type_converter_test.cc @@ -18,14 +18,10 @@ std::optional successor(std::optional solver_type) { case SolverType::kClp: return SolverType::kCsdp; case SolverType::kCsdp: - return SolverType::kDReal; - case SolverType::kDReal: return SolverType::kEqualityConstrainedQP; case SolverType::kEqualityConstrainedQP: return SolverType::kGurobi; case SolverType::kGurobi: - return SolverType::kIbex; - case SolverType::kIbex: return SolverType::kIpopt; case SolverType::kIpopt: return SolverType::kLinearSystem; @@ -44,6 +40,13 @@ std::optional successor(std::optional solver_type) { case SolverType::kSnopt: return SolverType::kUnrevisedLemke; case SolverType::kUnrevisedLemke: +#pragma GCC diagnostic push +#pragma GCC diagnostic ignored "-Wdeprecated-declarations" + return SolverType::kDReal; + case SolverType::kDReal: + return SolverType::kIbex; + case SolverType::kIbex: +#pragma GCC diagnostic pop return std::nullopt; } DRAKE_UNREACHABLE(); diff --git a/tools/workspace/cds/repository.bzl b/tools/workspace/cds/repository.bzl index 406906da1486..cd6cfaa0c3cd 100644 --- a/tools/workspace/cds/repository.bzl +++ b/tools/workspace/cds/repository.bzl @@ -2,6 +2,9 @@ load("@drake//tools/workspace:github.bzl", "github_archive") +# N.B. This repository is deprecated for removal on 2023-02-01. +# For details see https://github.com/RobotLocomotion/drake/pull/18156. + def cds_repository( name, mirrors = None): diff --git a/tools/workspace/default.bzl b/tools/workspace/default.bzl index f9bfe8e08825..db79bfa95243 100644 --- a/tools/workspace/default.bzl +++ b/tools/workspace/default.bzl @@ -127,6 +127,8 @@ def add_default_repositories(excludes = [], mirrors = DEFAULT_MIRRORS): if "ccd" not in excludes: ccd_repository(name = "ccd", mirrors = mirrors) if "cds" not in excludes: + # N.B. This repository is deprecated for removal on 2023-02-01. + # For details see https://github.com/RobotLocomotion/drake/pull/18156. cds_repository(name = "cds", mirrors = mirrors) if "clang_cindex_python3_internal" not in excludes: clang_cindex_python3_internal_repository(name = "clang_cindex_python3_internal", mirrors = mirrors) # noqa @@ -155,6 +157,8 @@ def add_default_repositories(excludes = [], mirrors = DEFAULT_MIRRORS): if "drake_visualizer" not in excludes: drake_visualizer_repository(name = "drake_visualizer", mirrors = mirrors) # noqa if "dreal" not in excludes: + # N.B. This repository is deprecated for removal on 2023-02-01. + # For details see https://github.com/RobotLocomotion/drake/pull/18156. dreal_repository(name = "dreal", mirrors = mirrors) if "eigen" not in excludes: eigen_repository(name = "eigen") @@ -189,6 +193,8 @@ def add_default_repositories(excludes = [], mirrors = DEFAULT_MIRRORS): if "gz_utils_internal" not in excludes: gz_utils_internal_repository(name = "gz_utils_internal", mirrors = mirrors) # noqa if "ibex" not in excludes: + # N.B. This repository is deprecated for removal on 2023-02-01. + # For details see https://github.com/RobotLocomotion/drake/pull/18156. ibex_repository(name = "ibex", mirrors = mirrors) if "intel_realsense_ros_internal" not in excludes: intel_realsense_ros_internal_repository(name = "intel_realsense_ros_internal", mirrors = mirrors) # noqa @@ -257,6 +263,8 @@ def add_default_repositories(excludes = [], mirrors = DEFAULT_MIRRORS): if "petsc" not in excludes: petsc_repository(name = "petsc", mirrors = mirrors) if "picosat" not in excludes: + # N.B. This repository is deprecated for removal on 2023-02-01. + # For details see https://github.com/RobotLocomotion/drake/pull/18156. picosat_repository(name = "picosat", mirrors = mirrors) if "picosha2" not in excludes: picosha2_repository(name = "picosha2", mirrors = mirrors) diff --git a/tools/workspace/dreal/repository.bzl b/tools/workspace/dreal/repository.bzl index 9467a4d0b043..1889b82a4c52 100644 --- a/tools/workspace/dreal/repository.bzl +++ b/tools/workspace/dreal/repository.bzl @@ -2,6 +2,9 @@ load("@drake//tools/workspace:github.bzl", "github_archive") +# N.B. This repository is deprecated for removal on 2023-02-01. +# For details see https://github.com/RobotLocomotion/drake/pull/18156. + def dreal_repository( name, mirrors = None): diff --git a/tools/workspace/ibex/repository.bzl b/tools/workspace/ibex/repository.bzl index a831266486d9..6dc9649ed616 100644 --- a/tools/workspace/ibex/repository.bzl +++ b/tools/workspace/ibex/repository.bzl @@ -2,13 +2,14 @@ load("@drake//tools/workspace:github.bzl", "github_archive") +# N.B. This repository is deprecated for removal on 2023-02-01. +# For details see https://github.com/RobotLocomotion/drake/pull/18156. + def ibex_repository( name, mirrors = None): github_archive( name = name, - # TODO(jwnimmer-tri) Switch to upstream ibex-lib (using local patch - # files if necessary). repository = "dreal-deps/ibex-lib", # As discussed in #15872, we need ibex < 2.8.7 for CLP support. commit = "115e12323529d524786c1a744f5ffce04f4783b5", # ibex-2.8.6_4 diff --git a/tools/workspace/picosat/repository.bzl b/tools/workspace/picosat/repository.bzl index 4e539a1ea8ad..7f5e04f73113 100644 --- a/tools/workspace/picosat/repository.bzl +++ b/tools/workspace/picosat/repository.bzl @@ -2,8 +2,8 @@ load("@drake//tools/workspace:github.bzl", "github_archive") -# TODO(jwnimmer-tri) For easier ugprades, stop using the dreal-deps mirror and -# switch to using the upstream archive at http://fmv.jku.at/picosat/. +# N.B. This repository is deprecated for removal on 2023-02-01. +# For details see https://github.com/RobotLocomotion/drake/pull/18156. def picosat_repository( name,