From ed7102c499a30f23583d904d60caa8b4f7c16d1b Mon Sep 17 00:00:00 2001 From: Jeremy Nimmer Date: Sun, 4 Feb 2024 08:20:02 -0800 Subject: [PATCH] Remove deprecated code 2024-02 Most of the removals are the past 3-4 months, but some MbT stuff dates back to 2020 but was overlooked previously. --- bindings/pydrake/multibody/BUILD.bazel | 1 - .../multibody/inverse_kinematics_py.cc | 177 ------ bindings/pydrake/multibody/plant_py.cc | 39 +- .../multibody/test/inverse_kinematics_test.py | 115 +--- bindings/pydrake/multibody/test/plant_test.py | 49 +- bindings/pydrake/multibody/tree_py.cc | 18 - .../pydrake/solvers/solvers_py_evaluators.cc | 95 ---- .../pydrake/solvers/test/evaluators_test.py | 88 +-- .../pydrake/systems/framework_py_systems.cc | 73 --- bindings/pydrake/systems/test/custom_test.py | 39 -- common/proto/call_python.h | 1 - common/symbolic/trigonometric_polynomial.h | 1 - common/trajectories/piecewise_polynomial.h | 1 - .../end_effector_teleop_dualshock4.py | 2 +- .../end_effector_teleop_mouse.py | 2 +- geometry/optimization/cspace_free_polytope.h | 1 - geometry/proximity/triangle_surface_mesh.h | 1 - geometry/proximity/volume_mesh.h | 1 - geometry/query_object.h | 1 - geometry/query_results/signed_distance_pair.h | 1 - .../query_results/signed_distance_to_point.h | 1 - geometry/render/render_engine.h | 1 - .../render_gl/internal_render_engine_gl.cc | 1 - .../internal_render_engine_gltf_client.cc | 1 - geometry/scene_graph.h | 1 - math/quaternion.h | 1 - multibody/inverse_kinematics/BUILD.bazel | 2 - .../differential_inverse_kinematics.h | 1 - .../inverse_kinematics/inverse_kinematics.cc | 14 - .../inverse_kinematics/inverse_kinematics.h | 31 -- .../minimum_distance_constraint.cc | 246 -------- .../minimum_distance_constraint.h | 258 --------- .../test/inverse_kinematics_test.cc | 52 -- .../test/minimum_distance_constraint_test.cc | 525 ------------------ multibody/plant/multibody_plant.h | 92 --- .../calc_distance_and_time_derivative_test.cc | 7 - multibody/plant/test/multibody_plant_test.cc | 51 -- multibody/tree/fixed_offset_frame.h | 1 - multibody/tree/frame.h | 1 - multibody/tree/mobilizer.h | 1 - multibody/tree/multibody_tree-inl.h | 1 - multibody/tree/multibody_tree.h | 53 -- multibody/tree/rigid_body.h | 19 - multibody/tree/test/multibody_tree_test.cc | 209 ------- multibody/tree/weld_joint.h | 1 - solvers/minimum_value_constraint.cc | 175 ------ solvers/minimum_value_constraint.h | 162 ------ solvers/test/minimum_value_constraint_test.cc | 299 +--------- systems/analysis/simulator.h | 3 +- systems/analysis/simulator_config_functions.h | 1 - systems/analysis/test/simulator_test.cc | 26 +- .../controllers/inverse_dynamics_controller.h | 1 - systems/framework/abstract_values.h | 1 - systems/framework/context_base.h | 16 - systems/framework/discrete_values.h | 1 - systems/framework/event.h | 7 +- systems/framework/event_collection.h | 29 +- systems/framework/fixed_input_port_value.h | 1 - systems/framework/framework_common.h | 1 - systems/framework/leaf_system.cc | 114 +--- systems/framework/leaf_system.h | 135 ----- systems/framework/output_port.h | 1 - systems/framework/subvector.h | 1 - systems/framework/system.cc | 1 - systems/framework/system.h | 20 +- systems/framework/test/leaf_context_test.cc | 12 - systems/framework/test/leaf_system_test.cc | 204 +------ systems/framework/test/system_test.cc | 4 +- systems/framework/test/vector_system_test.cc | 29 +- systems/framework/vector_system.h | 16 +- systems/lcm/lcm_subscriber_system.h | 1 - tools/workspace/default.bzl | 20 - tools/workspace/expat/BUILD.bazel | 6 - tools/workspace/expat/repository.bzl | 85 --- tools/workspace/libjpeg/BUILD.bazel | 6 - tools/workspace/libjpeg/package.BUILD.bazel | 19 - tools/workspace/libjpeg/repository.bzl | 55 -- tools/workspace/libpng/BUILD.bazel | 6 - tools/workspace/libpng/repository.bzl | 9 - tools/workspace/libtiff/BUILD.bazel | 6 - tools/workspace/libtiff/repository.bzl | 9 - .../visualization_config_functions.h | 1 - 82 files changed, 70 insertions(+), 3690 deletions(-) delete mode 100644 multibody/inverse_kinematics/minimum_distance_constraint.cc delete mode 100644 multibody/inverse_kinematics/minimum_distance_constraint.h delete mode 100644 tools/workspace/expat/BUILD.bazel delete mode 100644 tools/workspace/expat/repository.bzl delete mode 100644 tools/workspace/libjpeg/BUILD.bazel delete mode 100644 tools/workspace/libjpeg/package.BUILD.bazel delete mode 100644 tools/workspace/libjpeg/repository.bzl delete mode 100644 tools/workspace/libpng/BUILD.bazel delete mode 100644 tools/workspace/libpng/repository.bzl delete mode 100644 tools/workspace/libtiff/BUILD.bazel delete mode 100644 tools/workspace/libtiff/repository.bzl diff --git a/bindings/pydrake/multibody/BUILD.bazel b/bindings/pydrake/multibody/BUILD.bazel index 019ff38e17df..c0fff05087b6 100644 --- a/bindings/pydrake/multibody/BUILD.bazel +++ b/bindings/pydrake/multibody/BUILD.bazel @@ -477,7 +477,6 @@ drake_py_unittest( ":benchmarks_py", ":inverse_kinematics_py", ":parsing_py", - "//bindings/pydrake/common/test_utilities", "//bindings/pydrake/planning", ], ) diff --git a/bindings/pydrake/multibody/inverse_kinematics_py.cc b/bindings/pydrake/multibody/inverse_kinematics_py.cc index d84085665e81..bb6b543cdbf1 100644 --- a/bindings/pydrake/multibody/inverse_kinematics_py.cc +++ b/bindings/pydrake/multibody/inverse_kinematics_py.cc @@ -13,7 +13,6 @@ #include "drake/multibody/inverse_kinematics/gaze_target_constraint.h" #include "drake/multibody/inverse_kinematics/global_inverse_kinematics.h" #include "drake/multibody/inverse_kinematics/inverse_kinematics.h" -#include "drake/multibody/inverse_kinematics/minimum_distance_constraint.h" #include "drake/multibody/inverse_kinematics/minimum_distance_lower_bound_constraint.h" #include "drake/multibody/inverse_kinematics/minimum_distance_upper_bound_constraint.h" #include "drake/multibody/inverse_kinematics/orientation_constraint.h" @@ -164,14 +163,6 @@ PYBIND11_MODULE(inverse_kinematics, m) { cls_doc.context.doc) .def("get_mutable_context", &Class::get_mutable_context, py_rvp::reference_internal, cls_doc.get_mutable_context.doc); -#pragma GCC diagnostic push -#pragma GCC diagnostic ignored "-Wdeprecated-declarations" - cls.def("AddMinimumDistanceConstraint", - WrapDeprecated(cls_doc.AddMinimumDistanceConstraint.doc_deprecated, - &Class::AddMinimumDistanceConstraint), - py::arg("minimum_distance"), py::arg("threshold_distance") = 1.0, - cls_doc.AddMinimumDistanceConstraint.doc_deprecated); -#pragma GCC diagnostic pop } { using Class = AngleBetweenVectorsConstraint; @@ -463,174 +454,6 @@ PYBIND11_MODULE(inverse_kinematics, m) { py::keep_alive<1, 9>(), cls_doc.ctor.doc_autodiff); } - { -#pragma GCC diagnostic push -#pragma GCC diagnostic ignored "-Wdeprecated-declarations" - using Class = MinimumDistanceConstraint; - constexpr auto& cls_doc = doc.MinimumDistanceConstraint; - using Ptr = std::shared_ptr; - py::class_ minimum_distance_constraint( - m, "MinimumDistanceConstraint", cls_doc.doc_deprecated); - - const std::string dep_message = - "MinimumDistanceConstraint is deprecated. Use " - "MinimumDistanceLowerBoundConstraint if you want the smallest distance " - "to be lower bounded, or MinimumDistanceUpperBoundConstraint if you " - "want the smallest distance to be upper bounded. The deprecated code " - "will be removed from Drake on or after 2024-02-01.\n\n"; - minimum_distance_constraint - .def(py_init_deprecated( - dep_message + cls_doc.ctor.doc_double_no_upper_bound, - [](const multibody::MultibodyPlant* const plant, - double minimum_distance, - systems::Context* plant_context, - solvers::MinimumValuePenaltyFunction penalty_function, - double influence_distance_offset) { - return std::make_unique(plant, minimum_distance, - plant_context, penalty_function, - influence_distance_offset); - }), - py::arg("plant"), py::arg("minimum_distance"), - py::arg("plant_context"), - py::arg("penalty_function") = - solvers::MinimumValuePenaltyFunction{}, - py::arg("influence_distance_offset") = 1, - // Keep alive, reference: `self` keeps `plant` alive. - py::keep_alive<1, 2>(), - // Keep alive, reference: `self` keeps `plant_context` alive. - py::keep_alive<1, 4>(), cls_doc.ctor.doc_double_no_upper_bound) - .def(py_init_deprecated( - dep_message + cls_doc.ctor.doc_autodiff_no_upper_bound, - [](const multibody::MultibodyPlant* const plant, - double minimum_distance, - systems::Context* plant_context, - solvers::MinimumValuePenaltyFunction penalty_function, - double influence_distance_offset) { - return std::make_unique(plant, minimum_distance, - plant_context, penalty_function, - influence_distance_offset); - }), - py::arg("plant"), py::arg("minimum_distance"), - py::arg("plant_context"), - py::arg("penalty_function") = - solvers::MinimumValuePenaltyFunction{}, - py::arg("influence_distance_offset") = 1, - // Keep alive, reference: `self` keeps `plant` alive. - py::keep_alive<1, 2>(), - // Keep alive, reference: `self` keeps `plant_context` alive. - py::keep_alive<1, 4>(), cls_doc.ctor.doc_autodiff_no_upper_bound) - .def( - py_init_deprecated( - dep_message + cls_doc.ctor.doc_collision_checker_no_upper_bound, - [](const planning::CollisionChecker* collision_checker, - double minimum_distance, - planning::CollisionCheckerContext* - collision_checker_context, - PyPenaltyFunction penalty_function, - double influence_distance_offset) { - return std::make_unique( - collision_checker, minimum_distance, - collision_checker_context, - UnwrapPyPenaltyFunction(penalty_function), - influence_distance_offset); - }), - py::arg("collision_checker"), py::arg("minimum_distance"), - py::arg("collision_checker_context"), - py::arg("penalty_function") = - solvers::MinimumValuePenaltyFunction{}, - py::arg("influence_distance_offset") = 1, - // Keep alive, reference: `self` keeps collision_checker - // alive. - py::keep_alive<1, 2>(), - // Keep alive, reference: `self` keeps collision_checker_context - // alive. - py::keep_alive<1, 4>(), - cls_doc.ctor.doc_collision_checker_no_upper_bound) - .def(py_init_deprecated( - dep_message + - cls_doc.ctor.doc_collision_checker_with_upper_bound, - [](const planning::CollisionChecker* collision_checker, - double minimum_distance_lower, - double minimum_distance_upper, - planning::CollisionCheckerContext* - collision_checker_context, - PyPenaltyFunction penalty_function, - double influence_distance) { - return std::make_unique( - collision_checker, minimum_distance_lower, - minimum_distance_upper, collision_checker_context, - UnwrapPyPenaltyFunction(penalty_function), - influence_distance); - }), - py::arg("collision_checker"), py::arg("minimum_distance_lower"), - py::arg("minimum_distance_upper"), - py::arg("collision_checker_context"), py::arg("penalty_function"), - py::arg("influence_distance"), - // Keep alive, reference: `self` keeps `collision_checker` - // alive. - py::keep_alive<1, 2>(), - // Keep alive, reference: `self` keeps `collision_checker_context` - // alive. - py::keep_alive<1, 5>(), - cls_doc.ctor.doc_collision_checker_with_upper_bound); - - std::string py_penalty_doc = - "\nThe penalty function penalty_function(x: float, compute_grad: bool) " - "-> tuple[float, Optional[float]] returns [penalty_val, " - "penalty_gradient] when compute_grad=True, or [penalty_value, None] " - "when compute_grad=False. See minimum_value_constraint.h on the " - "requirement on MinimumValuePenaltyFunction. Set " - "`penalty_function=None` and then the constraint will use the default " - "penalty function.\n\n"; - const std::string constructor_double_with_upper_bound_doc = - cls_doc.ctor.doc_double_with_upper_bound + py_penalty_doc; - - minimum_distance_constraint.def( - py_init_deprecated( - dep_message + constructor_double_with_upper_bound_doc, - [](const multibody::MultibodyPlant* plant, - double minimum_distance_lower, double minimum_distance_upper, - systems::Context* plant_context, - PyPenaltyFunction penalty_function, double influence_distance) { - return std::make_unique(plant, - minimum_distance_lower, minimum_distance_upper, plant_context, - UnwrapPyPenaltyFunction(penalty_function), - influence_distance); - }), - py::arg("plant"), py::arg("minimum_distance_lower"), - py::arg("minimum_distance_upper"), py::arg("plant_context"), - py::arg("penalty_function"), py::arg("influence_distance"), - // Keep alive, reference: `self` keeps `plant` alive. - py::keep_alive<1, 2>(), - // Keep alive, reference: `self` keeps `plant_context` alive. - py::keep_alive<1, 5>(), - constructor_double_with_upper_bound_doc.c_str()); - - const std::string constructor_autodiff_with_upper_bound_doc = - cls_doc.ctor.doc_autodiff_with_upper_bound + py_penalty_doc; - minimum_distance_constraint.def( - py_init_deprecated( - dep_message + constructor_autodiff_with_upper_bound_doc, - [](const multibody::MultibodyPlant* plant, - double minimum_distance_lower, double minimum_distance_upper, - systems::Context* plant_context, - PyPenaltyFunction penalty_function, double influence_distance) { - return std::make_unique(plant, - minimum_distance_lower, minimum_distance_upper, plant_context, - UnwrapPyPenaltyFunction(penalty_function), - influence_distance); - }), - py::arg("plant"), py::arg("minimum_distance_lower"), - py::arg("minimum_distance_upper"), py::arg("plant_context"), - py::arg("penalty_function"), py::arg("influence_distance"), - // Keep alive, reference: `self` keeps `plant` alive. - py::keep_alive<1, 2>(), - // Keep alive, reference: `self` keeps `plant_context` alive. - py::keep_alive<1, 5>(), - constructor_autodiff_with_upper_bound_doc.c_str()); -#pragma GCC diagnostic pop - } - { using Class = MinimumDistanceLowerBoundConstraint; constexpr auto& cls_doc = doc.MinimumDistanceLowerBoundConstraint; diff --git a/bindings/pydrake/multibody/plant_py.cc b/bindings/pydrake/multibody/plant_py.cc index 992f0fad8a05..84d23004acf5 100644 --- a/bindings/pydrake/multibody/plant_py.cc +++ b/bindings/pydrake/multibody/plant_py.cc @@ -1071,44 +1071,7 @@ void DoScalarDependentDefinitions(py::module m, T) { &Class::get_contact_penalty_method_time_scale, cls_doc.get_contact_penalty_method_time_scale.doc) .def("set_stiction_tolerance", &Class::set_stiction_tolerance, - py::arg("v_stiction") = 0.001, cls_doc.set_stiction_tolerance.doc); -#pragma GCC diagnostic push -#pragma GCC diagnostic ignored "-Wdeprecated-declarations" - // Position and velocity accessors and mutators. - cls // BR - .def("GetMutablePositionsAndVelocities", - WrapDeprecated( - cls_doc.GetMutablePositionsAndVelocities.doc_deprecated, - [](const MultibodyPlant* self, - Context* context) -> Eigen::Ref> { - return self->GetMutablePositionsAndVelocities(context); - }), - py_rvp::reference, py::arg("context"), - // Keep alive, ownership: `return` keeps `context` alive. - py::keep_alive<0, 2>(), - cls_doc.GetMutablePositionsAndVelocities.doc_deprecated) - .def("GetMutablePositions", - WrapDeprecated(cls_doc.GetMutablePositions.doc_deprecated_1args, - [](const MultibodyPlant* self, - Context* context) -> Eigen::Ref> { - return self->GetMutablePositions(context); - }), - py_rvp::reference, py::arg("context"), - // Keep alive, ownership: `return` keeps `context` alive. - py::keep_alive<0, 2>(), - cls_doc.GetMutablePositions.doc_deprecated_1args) - .def("GetMutableVelocities", - WrapDeprecated(cls_doc.GetMutableVelocities.doc_deprecated_1args, - [](const MultibodyPlant* self, - Context* context) -> Eigen::Ref> { - return self->GetMutableVelocities(context); - }), - py_rvp::reference, py::arg("context"), - // Keep alive, ownership: `return` keeps `context` alive. - py::keep_alive<0, 2>(), - cls_doc.GetMutableVelocities.doc_deprecated_1args); -#pragma GCC diagnostic pop - cls // BR + py::arg("v_stiction") = 0.001, cls_doc.set_stiction_tolerance.doc) .def( "GetPositions", [](const MultibodyPlant* self, const Context& context) diff --git a/bindings/pydrake/multibody/test/inverse_kinematics_test.py b/bindings/pydrake/multibody/test/inverse_kinematics_test.py index 0e585dfc90f4..ed8b714d233d 100644 --- a/bindings/pydrake/multibody/test/inverse_kinematics_test.py +++ b/bindings/pydrake/multibody/test/inverse_kinematics_test.py @@ -12,7 +12,6 @@ import pydrake from pydrake.common import FindResourceOrThrow from pydrake.common.eigen_geometry import Quaternion -from pydrake.common.test_utilities.deprecation import catch_drake_warnings from pydrake.math import RigidTransform, RotationMatrix from pydrake.multibody.parsing import Parser from pydrake.multibody.plant import ( @@ -379,43 +378,6 @@ def test_AddPolyhedronConstraint(self): result = mp.Solve(self.prog) self.assertTrue(result.is_success()) - def test_AddMinimumDistanceConstraint(self): - ik = self.ik_two_bodies - W = self.plant.world_frame() - B1 = self.body1_frame - B2 = self.body2_frame - - min_distance = 0.1 - tol = 1e-2 - radius1 = 0.1 - radius2 = 0.2 - - with catch_drake_warnings(expected_count=1): - ik.AddMinimumDistanceConstraint(minimum_distance=min_distance) - context = self.plant.CreateDefaultContext() - self.plant.SetFreeBodyPose( - context, B1.body(), RigidTransform([0, 0, 0.01])) - self.plant.SetFreeBodyPose( - context, B2.body(), RigidTransform([0, 0, -0.01])) - - def get_min_distance_actual(): - X = partial(self.plant.CalcRelativeTransform, context) - distance = np.linalg.norm( - X(W, B1).translation() - X(W, B2).translation()) - return distance - radius1 - radius2 - - self.assertLess(get_min_distance_actual(), min_distance - tol) - self.prog.SetInitialGuess(ik.q(), self.plant.GetPositions(context)) - result = mp.Solve(self.prog) - self.assertTrue(result.is_success()) - q_val = result.GetSolution(ik.q()) - self.plant.SetPositions(context, q_val) - self.assertGreater(get_min_distance_actual(), min_distance - tol) - - result = mp.Solve(self.prog) - self.assertTrue(result.is_success()) - self.assertTrue(np.allclose(result.GetSolution(ik.q()), q_val)) - def test_AddMinimumDistanceLowerBoundConstraint(self): ik = self.ik_two_bodies W = self.plant.world_frame() @@ -612,51 +574,6 @@ def test_gaze_target_constraint(self, variables): plant_context=variables.plant_context) self.assertIsInstance(constraint, mp.Constraint) - @check_type_variables - def test_minimum_distance_constraint(self, variables): - with catch_drake_warnings(expected_count=1): - constraint = ik.MinimumDistanceConstraint( - plant=variables.plant, - minimum_distance=0.1, - plant_context=variables.plant_context) - self.assertIsInstance(constraint, mp.Constraint) - - # Now set the new penalty function - def penalty_fun(x: float, compute_grad: bool) \ - -> typing.Tuple[float, typing.Optional[float]]: - if x < 0: - if compute_grad: - return x**2, 2 * x - else: - return x**2, None - else: - if compute_grad: - return 0., 0. - else: - return 0., None - - with catch_drake_warnings(expected_count=1): - constraint = ik.MinimumDistanceConstraint( - plant=variables.plant, minimum_distance_lower=0.1, - minimum_distance_upper=1, - plant_context=variables.plant_context, - penalty_function=penalty_fun, influence_distance=3) - self.assertIsInstance(constraint, mp.Constraint) - - q = variables.plant.GetPositions(variables.plant_context) - y = constraint.Eval(q) - - # Now test the case with penalty_function=None. It will use the - # default penalty function. - with catch_drake_warnings(expected_count=1): - constraint = ik.MinimumDistanceConstraint( - plant=variables.plant, minimum_distance_lower=0.1, - minimum_distance_upper=1, - plant_context=variables.plant_context, - penalty_function=None, influence_distance=3) - self.assertIsInstance(constraint, mp.Constraint) - y_default_penalty = constraint.Eval(q) - @check_type_variables def test_minimum_distance_lower_bound_constraint(self, variables): constraint = ik.MinimumDistanceLowerBoundConstraint( @@ -765,8 +682,9 @@ def _make_robot_diagram(self): robot_diagram = builder.Build() return (robot_diagram, model_instance_index) - def test_minimum_distance_constraint_with_collision_checker(self): - # test the MinimumDistanceConstraint with CollisionChecker. + def test_minimum_distance_constraints_with_collision_checker(self): + # Test the MinimumDistance{Lower,Upper}BoundConstraint with + # CollisionChecker. robot, index = self._make_robot_diagram() def distance_function(q1, q2): @@ -779,23 +697,18 @@ def distance_function(q1, q2): edge_step_size=0.125) collision_checker_context = \ collision_checker.MakeStandaloneModelContext() - # Construct without minimum_distance_upper. - with catch_drake_warnings(expected_count=1): - constraint = ik.MinimumDistanceConstraint( - collision_checker=collision_checker, minimum_distance=0.01, - collision_checker_context=collision_checker_context, - penalty_function=None, influence_distance_offset=0.1) - self.assertIsInstance(constraint, mp.Constraint) - # Construct with minimum_distance_upper. - with catch_drake_warnings(expected_count=1): - constraint = ik.MinimumDistanceConstraint( - collision_checker=collision_checker, - minimum_distance_lower=0.01, - minimum_distance_upper=0.1, - collision_checker_context=collision_checker_context, - penalty_function=None, influence_distance=0.2) - self.assertIsInstance(constraint, mp.Constraint) + constraint_lower = ik.MinimumDistanceLowerBoundConstraint( + collision_checker=collision_checker, bound=0.01, + collision_checker_context=collision_checker_context, + penalty_function=None, influence_distance_offset=0.1) + self.assertIsInstance(constraint_lower, mp.Constraint) + + constraint_upper = ik.MinimumDistanceUpperBoundConstraint( + collision_checker=collision_checker, bound=0.1, + collision_checker_context=collision_checker_context, + penalty_function=None, influence_distance_offset=0.2) + self.assertIsInstance(constraint_upper, mp.Constraint) @check_type_variables def test_position_constraint(self, variables): diff --git a/bindings/pydrake/multibody/test/plant_test.py b/bindings/pydrake/multibody/test/plant_test.py index 3157ba824611..8de3277bfcbc 100644 --- a/bindings/pydrake/multibody/test/plant_test.py +++ b/bindings/pydrake/multibody/test/plant_test.py @@ -1266,26 +1266,12 @@ def test_multibody_state_access(self, T): x = plant.GetPositionsAndVelocities(context) numpy_compare.assert_float_equal(x, np.zeros(4)) - # WARNING: The following oddities occur from the fact that - # `ndarray[object]` cannot be referenced (#8116). Be careful when - # writing scalar-generic code. - if T == float: - # Can reference matrices. Use `x_ref`. - # Write into a mutable reference to the state vector. - with catch_drake_warnings(expected_count=1) as w: - x_ref = plant.GetMutablePositionsAndVelocities(context) - x_ref[:] = x0 - - def set_zero(): - x_ref.fill(0) - - else: - # Cannot reference matrices. Use setters. - plant.SetPositionsAndVelocities(context, x0) + # A convenience function to reset back to zero. + def set_zero(): + plant.SetPositionsAndVelocities(context, np.zeros(nq + nv)) - def set_zero(): - plant.SetPositionsAndVelocities( - context, np.zeros(nq + nv)) + # Change x to non-zero values. + plant.SetPositionsAndVelocities(context, x0) # Verify that positions and velocities were set correctly. numpy_compare.assert_float_equal(plant.GetPositions(context), q0) @@ -1319,15 +1305,6 @@ def set_zero(): plant.SetDefaultPositions(model_instance=instance, q_instance=q0) plant.GetDefaultPositions(model_instance=instance) - if T == float: - # Test GetMutablePositions/Velocities - with catch_drake_warnings(expected_count=1) as w: - q_ref = plant.GetMutablePositions(context) - q_ref[:] = q0 - with catch_drake_warnings(expected_count=1) as w: - v_ref = plant.GetMutableVelocities(context) - v_ref[:] = v0 - # Test existence of context resetting methods. plant.SetDefaultState(context, state=context.get_mutable_state()) @@ -1756,22 +1733,13 @@ def test_model_instance_state_access_by_array(self, T): x_desired[nq:nq+7] = v_iiwa_desired x_desired[nq+7:nq+nv] = v_gripper_desired - if T == float: - with catch_drake_warnings(expected_count=1) as w: - x = plant.GetMutablePositionsAndVelocities(context=context) - x[:] = x_desired - else: - plant.SetPositionsAndVelocities(context, x_desired) + plant.SetPositionsAndVelocities(context, x_desired) q = plant.GetPositions(context=context) v = plant.GetVelocities(context=context) # Get state from context. x = plant.GetPositionsAndVelocities(context=context) - if T == float: - with catch_drake_warnings(expected_count=1) as w: - x_tmp = plant.GetMutablePositionsAndVelocities(context=context) - self.assertTrue(np.allclose(x_desired, x_tmp)) # Get positions and velocities of specific model instances # from the position/velocity vector of the plant. @@ -1850,8 +1818,6 @@ def test_map_qdot_to_v_and_back(self, T): [0.4, 0.5, 0.6]) self.assertNotEqual(link0.floating_positions_start(), -1) self.assertNotEqual(link0.floating_velocities_start_in_v(), -1) - with catch_drake_warnings(expected_count=1): - self.assertNotEqual(link0.floating_velocities_start(), -1) self.assertFalse(plant.IsVelocityEqualToQDot()) v_expected = np.linspace(start=-1.0, stop=-nv, num=nv) qdot = plant.MapVelocityToQDot(context, v_expected) @@ -2005,9 +1971,6 @@ def loop_body(make_joint, time_step): u = np.array([0.1]) numpy_compare.assert_float_equal( actuator.get_actuation_vector(u=u), [0.1]) - with catch_drake_warnings(expected_count=1): - actuator.set_actuation_vector( - u_instance=np.array([0.2]), u=u) actuator.set_actuation_vector( u_actuator=np.array([0.2]), u=u) numpy_compare.assert_float_equal(u, [0.2]) diff --git a/bindings/pydrake/multibody/tree_py.cc b/bindings/pydrake/multibody/tree_py.cc index 7869f5d0fb12..f16054a073da 100644 --- a/bindings/pydrake/multibody/tree_py.cc +++ b/bindings/pydrake/multibody/tree_py.cc @@ -394,16 +394,6 @@ void DoScalarDependentDefinitions(py::module m, T) { &Class::SetSpatialInertiaInBodyFrame, py::arg("context"), py::arg("M_Bo_B"), cls_doc.SetSpatialInertiaInBodyFrame.doc); -// TODO(sherm1) Remove as of 2024-02-01. -#pragma GCC diagnostic push -#pragma GCC diagnostic ignored "-Wdeprecated-declarations" - cls // BR - .def("floating_velocities_start", - WrapDeprecated(cls_doc.floating_velocities_start.doc_deprecated, - &Class::floating_velocities_start), - cls_doc.floating_velocities_start.doc_deprecated); -#pragma GCC diagnostic pop - // Aliases for backwards compatibility (dispreferred). m.attr("Body") = m.attr("RigidBody"); m.attr("Body_") = m.attr("RigidBody_"); @@ -862,14 +852,6 @@ void DoScalarDependentDefinitions(py::module m, T) { py::arg("gains"), cls_doc.set_controller_gains.doc) .def("has_controller", &Class::has_controller, cls_doc.has_controller.doc); - constexpr char doc_deprecated_set_actuation_vector[] = - "The kwarg name 'u_instance' is deprecated and will be removed on " - "2024-02-01. Spell the argument name as 'u_actuator' instead."; - cls.def("set_actuation_vector", - WrapDeprecated( - doc_deprecated_set_actuation_vector, &Class::set_actuation_vector), - py::arg("u_instance"), py::arg("u"), - doc_deprecated_set_actuation_vector); } // Force Elements. diff --git a/bindings/pydrake/solvers/solvers_py_evaluators.cc b/bindings/pydrake/solvers/solvers_py_evaluators.cc index dd8d849a28e4..3f4b54e46362 100644 --- a/bindings/pydrake/solvers/solvers_py_evaluators.cc +++ b/bindings/pydrake/solvers/solvers_py_evaluators.cc @@ -39,10 +39,6 @@ using solvers::LinearEqualityConstraint; using solvers::LinearMatrixInequalityConstraint; using solvers::LInfNormCost; using solvers::LorentzConeConstraint; -#pragma GCC diagnostic push -#pragma GCC diagnostic ignored "-Wdeprecated-declarations" -using solvers::MinimumValueConstraint; -#pragma GCC diagnostic pop using solvers::MinimumValueLowerBoundConstraint; using solvers::MinimumValueUpperBoundConstraint; using solvers::PerspectiveQuadraticCost; @@ -480,93 +476,6 @@ void BindEvaluatorsAndBindings(py::module m) { // dtype = object arrays must be copied, and cannot be referenced. py_rvp::copy, doc.ExpressionConstraint.vars.doc); -#pragma GCC diagnostic push -#pragma GCC diagnostic ignored "-Wdeprecated-declarations" - const std::string dep_message = - "MinimumValueConstraint is deprecated. Use " - "MinimumValueLowerBoundConstraint if you want the smallest value to be " - "lower bounded, or MinimumValueUpperBoundConstraint if you want the " - "smallest value to be upper bounded. The deprecated code will be removed " - "from Drake on or after 2024-02-01.\n\n"; - py::class_>( - m, "MinimumValueConstraint", doc.MinimumValueConstraint.doc_deprecated) - .def(py_init_deprecated( - dep_message + doc.MinimumValueConstraint.ctor.doc_6args, - [](int num_vars, double minimum_value, - double influence_value_offset, int max_num_values, - // If I pass in const Eigen::Ref& here - // then I got the RuntimeError: dtype=object arrays must be - // copied, and cannot be referenced. - std::function - value_function, - std::function&, double)> - value_function_double) { - return std::make_unique(num_vars, - minimum_value, influence_value_offset, max_num_values, - value_function, value_function_double); - }), - py::arg("num_vars"), py::arg("minimum_value"), - py::arg("influence_value_offset"), py::arg("max_num_values"), - py::arg("value_function"), - py::arg("value_function_double") = std::function&, double)>{}, - doc.MinimumValueConstraint.ctor.doc_6args) - .def(py_init_deprecated( - dep_message + doc.MinimumValueConstraint.ctor.doc_7args, - [](int num_vars, double minimum_value_lower, - double minimum_value_upper, double influence_value, - int max_num_values, - // If I pass in const Eigen::Ref& here - // then I got the RuntimeError: dtype=object arrays must be - // copied, and cannot be referenced. - std::function - value_function, - std::function&, double)> - value_function_double) { - return std::make_unique(num_vars, - minimum_value_lower, minimum_value_upper, influence_value, - max_num_values, value_function, value_function_double); - }), - py::arg("num_vars"), py::arg("minimum_value_lower"), - py::arg("minimum_value_upper"), py::arg("influence_value"), - py::arg("max_num_values"), py::arg("value_function"), - py::arg("value_function_double") = std::function&, double)>{}, - doc.MinimumValueConstraint.ctor.doc_7args) - .def("minimum_value_lower", &MinimumValueConstraint::minimum_value_lower, - doc.MinimumValueConstraint.minimum_value_lower.doc) - .def("minimum_value_upper", &MinimumValueConstraint::minimum_value_upper, - doc.MinimumValueConstraint.minimum_value_upper.doc) - .def("influence_value", &MinimumValueConstraint::influence_value, - doc.MinimumValueConstraint.influence_value.doc) - .def( - "set_penalty_function", - [](MinimumValueConstraint* self, - std::function new_penalty_function) { - auto penalty_fun = [new_penalty_function](double x, double* penalty, - double* dpenalty) { - py::tuple penalty_tuple(2); - penalty_tuple = new_penalty_function(x, dpenalty != nullptr); - *penalty = penalty_tuple[0].cast(); - if (dpenalty) { - *dpenalty = penalty_tuple[1].cast(); - } - }; - self->set_penalty_function(penalty_fun); - }, - py::arg("new_penalty_function"), - "Setter for the penalty function. The penalty function " - "new_penalty_function(x: float, compute_grad: bool) -> tuple[float, " - "Optional[float]] " - "returns [penalty_value, penalty_gradient] when " - "compute_grad=True, or [penalty_value, None] when " - "compute_grad=False. See minimum_value_constraint.h on the " - "requirement on MinimumValuePenaltyFunction."); -#pragma GCC diagnostic pop - py::class_>(m, "MinimumValueLowerBoundConstraint", @@ -689,10 +598,6 @@ void BindEvaluatorsAndBindings(py::module m) { RegisterBinding(&m); RegisterBinding(&m); RegisterBinding(&m); -#pragma GCC diagnostic push -#pragma GCC diagnostic ignored "-Wdeprecated-declarations" - RegisterBinding(&m); -#pragma GCC diagnostic pop RegisterBinding(&m); RegisterBinding(&m); // TODO(russt): PolynomialConstraint currently uses common::Polynomial, not diff --git a/bindings/pydrake/solvers/test/evaluators_test.py b/bindings/pydrake/solvers/test/evaluators_test.py index 4d954e12bf4f..71d66e042cc0 100644 --- a/bindings/pydrake/solvers/test/evaluators_test.py +++ b/bindings/pydrake/solvers/test/evaluators_test.py @@ -219,7 +219,8 @@ def test_binding_instantiations(self): mp.LinearMatrixInequalityConstraint, mp.LinearComplementarityConstraint, mp.ExponentialConeConstraint, - mp.MinimumValueConstraint, + mp.MinimumValueLowerBoundConstraint, + mp.MinimumValueUpperBoundConstraint, mp.Cost, mp.LinearCost, mp.QuadraticCost, @@ -232,94 +233,11 @@ def test_binding_instantiations(self): mp.Binding[cls] -# A dummy value function for MinimumValueConstraint. +# A dummy value function for MinimumValue{Lower,Upper}BoundConstraint. def value_function(x: np.ndarray, v_influence: float) -> np.ndarray: return np.array([x[0]**2, x[0]+1, 2*x[0]]) -class TestMinimumValueConstraint(unittest.TestCase): - def test_without_minimum_value_upper(self): - # Test the constructor with value_function_double explicitly specified. - with catch_drake_warnings(expected_count=1): - dut = mp.MinimumValueConstraint( - num_vars=1, minimum_value=0., - influence_value_offset=1., max_num_values=3, - value_function=value_function, - value_function_double=value_function) - self.assertEqual(dut.num_vars(), 1) - self.assertEqual(dut.num_constraints(), 1) - self.assertTrue(dut.CheckSatisfied(np.array([1.]))) - self.assertFalse(dut.CheckSatisfied(np.array([-5.]))) - # Evaluate with autodiff. - y = dut.Eval(InitializeAutoDiff(np.array([1.]))) - self.assertEqual(dut.minimum_value_lower(), 0.) - self.assertTrue(np.isinf(dut.minimum_value_upper())) - self.assertEqual(dut.influence_value(), 1.) - - # Test the constructor with default value_function_double. - with catch_drake_warnings(expected_count=1): - dut = mp.MinimumValueConstraint( - num_vars=1, minimum_value=0., - influence_value_offset=1., max_num_values=3, - value_function=value_function) - self.assertTrue(dut.CheckSatisfied(np.array([1.]))) - self.assertFalse(dut.CheckSatisfied(np.array([-5.]))) - - def test_with_minimum_value_upper(self): - # Test the constructor with value_function_double explicitly specified. - with catch_drake_warnings(expected_count=1): - dut = mp.MinimumValueConstraint( - num_vars=1, minimum_value_lower=0., minimum_value_upper=1.5, - influence_value=3., max_num_values=3, - value_function=value_function, - value_function_double=value_function) - self.assertEqual(dut.num_vars(), 1) - self.assertEqual(dut.num_constraints(), 2) - self.assertTrue(dut.CheckSatisfied(np.array([1.]))) - self.assertFalse(dut.CheckSatisfied(np.array([-5.]))) - # Evaluate with autodiff. - y = dut.Eval(InitializeAutoDiff(np.array([1.]))) - - # Test the constructor with default value_function_double. - with catch_drake_warnings(expected_count=1): - dut = mp.MinimumValueConstraint( - num_vars=1, minimum_value_lower=0., minimum_value_upper=1.5, - influence_value=3., max_num_values=3, - value_function=value_function) - self.assertTrue(dut.CheckSatisfied(np.array([1.]))) - self.assertFalse(dut.CheckSatisfied(np.array([-5.]))) - - def test_set_penalty_function(self): - with catch_drake_warnings(expected_count=1): - dut = mp.MinimumValueConstraint( - num_vars=1, minimum_value_lower=0., minimum_value_upper=1.5, - influence_value=3., max_num_values=3, - value_function=value_function, - value_function_double=value_function) - - # Now set the new penalty function - def penalty(x: float, compute_grad: bool)\ - -> typing.Tuple[float, typing.Optional[float]]: - if x < 0: - if compute_grad: - return x**2, 2 * x - else: - return x**2, None - else: - if compute_grad: - return 0., 0. - else: - return 0., None - - dut.set_penalty_function(new_penalty_function=penalty) - self.assertTrue(dut.CheckSatisfied(np.array([1.]))) - self.assertFalse(dut.CheckSatisfied(np.array([-5.]))) - self.assertTrue( - dut.CheckSatisfied(InitializeAutoDiff(np.array([1.])))) - self.assertFalse( - dut.CheckSatisfied(InitializeAutoDiff(np.array([5.])))) - - class TestMinimumValueLowerBoundConstraint(unittest.TestCase): def test_constructor(self): # Test the constructor with value_function_double explicitly specified. diff --git a/bindings/pydrake/systems/framework_py_systems.cc b/bindings/pydrake/systems/framework_py_systems.cc index 00b393f6d784..9885d2df319c 100644 --- a/bindings/pydrake/systems/framework_py_systems.cc +++ b/bindings/pydrake/systems/framework_py_systems.cc @@ -110,12 +110,6 @@ struct Impl { // downcasting when trying to bind `PyLeafSystem::DoCalcTimeDerivatives` to // `py::class_, ...>`. using Base::DoCalcTimeDerivatives; - - // To be removed with deprecation on 2024-02-01. - using Base::DeclarePeriodicDiscreteUpdateNoHandler; - using Base::DeclarePeriodicPublishNoHandler; - using Base::DoCalcDiscreteVariableUpdates; - using Base::DoPublish; }; // Provide flexible inheritance to leverage prior binding information, per @@ -129,16 +123,6 @@ struct Impl { // Trampoline virtual methods. - void DoPublish(const Context& context, - const vector*>& events) const override { - PYBIND11_OVERLOAD_INT(void, LeafSystem, "DoPublish", &context, events); - // If the macro did not return, use default functionality. -#pragma GCC diagnostic push -#pragma GCC diagnostic ignored "-Wdeprecated-declarations" - Base::DoPublish(context, events); -#pragma GCC diagnostic pop - } - void DoCalcTimeDerivatives(const Context& context, ContinuousState* derivatives) const override { // Yuck! We have to dig in and use internals :( @@ -153,18 +137,6 @@ struct Impl { Base::DoCalcTimeDerivatives(context, derivatives); } - void DoCalcDiscreteVariableUpdates(const Context& context, - const std::vector*>& events, - DiscreteValues* discrete_state) const override { - PYBIND11_OVERLOAD_INT(void, LeafSystem, - "DoCalcDiscreteVariableUpdates", &context, events, discrete_state); - // If the macro did not return, use default functionality. -#pragma GCC diagnostic push -#pragma GCC diagnostic ignored "-Wdeprecated-declarations" - Base::DoCalcDiscreteVariableUpdates(context, events, discrete_state); -#pragma GCC diagnostic pop - } - // This actually changes the signature of DoGetWitnessFunction, // expecting the python overload to return a list of witnesses (instead // of taking in an empty pointer to std::vector<>. @@ -249,20 +221,6 @@ struct Impl { using Base = py::wrapper; using Base::Base; - // Trampoline virtual methods. - void DoPublish(const Context& context, - const vector*>& events) const override { - // Copied from above, since we cannot use `PyLeafSystemBase` due to final - // overrides of some methods. - PYBIND11_OVERLOAD_INT( - void, VectorSystem, "DoPublish", &context, events); - // If the macro did not return, use default functionality. -#pragma GCC diagnostic push -#pragma GCC diagnostic ignored "-Wdeprecated-declarations" - Base::DoPublish(context, events); -#pragma GCC diagnostic pop - } - void DoCalcVectorOutput(const Context& context, const Eigen::VectorBlock>& input, const Eigen::VectorBlock>& state, @@ -977,37 +935,6 @@ Note: The above is for the C++ documentation. For Python, use py::overload_cast( &LeafSystemPublic::DeclareAbstractState), py::arg("model_value"), doc.LeafSystem.DeclareAbstractState.doc); -#pragma GCC diagnostic push -#pragma GCC diagnostic ignored "-Wdeprecated-declarations" - leaf_system_cls // BR - .def("DeclarePeriodicPublishNoHandler", - WrapDeprecated( - doc.LeafSystem.DeclarePeriodicPublishNoHandler.doc_deprecated, - &LeafSystemPublic::DeclarePeriodicPublishNoHandler), - py::arg("period_sec"), py::arg("offset_sec") = 0., - doc.LeafSystem.DeclarePeriodicPublishNoHandler.doc_deprecated) - .def("DeclarePeriodicDiscreteUpdateNoHandler", - WrapDeprecated(doc.LeafSystem.DeclarePeriodicDiscreteUpdateNoHandler - .doc_deprecated, - &LeafSystemPublic::DeclarePeriodicDiscreteUpdateNoHandler), - py::arg("period_sec"), py::arg("offset_sec") = 0., - doc.LeafSystem.DeclarePeriodicDiscreteUpdateNoHandler - .doc_deprecated) - .def("DoPublish", - WrapDeprecated( - "Directly calling DoPublish() is no longer allowed. Use " - "ForcedPublish() instead. " - "This function will be removed from Drake on 2024-02-01.", - &LeafSystemPublic::DoPublish), - doc.LeafSystem.DoPublish.doc) - .def("DoCalcDiscreteVariableUpdates", - WrapDeprecated( - "Directly calling DoCalcDiscreteVariableUpdates() is no longer " - "allowed. Use CalcForcedDiscreteVariableUpdate() instead. " - "This function will be removed from Drake on 2024-02-01.", - &LeafSystemPublic::DoCalcDiscreteVariableUpdates), - doc.LeafSystem.DoCalcDiscreteVariableUpdates.doc); -#pragma GCC diagnostic pop DefineTemplateClassWithDefault, PyDiagram, System>( m, "Diagram", GetPyParam(), doc.Diagram.doc) diff --git a/bindings/pydrake/systems/test/custom_test.py b/bindings/pydrake/systems/test/custom_test.py index f18d21c66a79..f241121560c6 100644 --- a/bindings/pydrake/systems/test/custom_test.py +++ b/bindings/pydrake/systems/test/custom_test.py @@ -9,7 +9,6 @@ import numpy as np from pydrake.autodiffutils import AutoDiffXd -from pydrake.common.test_utilities.deprecation import catch_drake_warnings from pydrake.common.value import Value from pydrake.symbolic import Expression from pydrake.systems.analysis import ( @@ -352,9 +351,7 @@ def test_all_leaf_system_overrides(self): class TrivialSystem(LeafSystem): def __init__(self): LeafSystem.__init__(self) - self.called_publish = False self.called_continuous = False - self.called_discrete = False self.called_initialize = False self.called_per_step = False self.called_periodic = False @@ -376,13 +373,6 @@ def __init__(self): self.called_reset = False self.called_system_reset = False # Ensure we have desired overloads. - with catch_drake_warnings(expected_count=1): - self.DeclarePeriodicPublishNoHandler(1.0) - with catch_drake_warnings(expected_count=1): - self.DeclarePeriodicPublishNoHandler(1.0, 0) - with catch_drake_warnings(expected_count=1): - self.DeclarePeriodicPublishNoHandler( - period_sec=1.0, offset_sec=0) self.DeclareInitializationPublishEvent( publish=self._on_initialize_publish) self.DeclareInitializationDiscreteUpdateEvent( @@ -393,9 +383,6 @@ def __init__(self): event=PublishEvent( trigger_type=TriggerType.kInitialization, callback=self._on_initialize)) - with catch_drake_warnings(expected_count=1): - self.DeclarePeriodicDiscreteUpdateNoHandler( - period_sec=1.0, offset_sec=0.) self.DeclarePeriodicPublishEvent( period_sec=1.0, offset_sec=0, @@ -465,32 +452,12 @@ def __init__(self): self.system_reset_witness, ] - def DoPublish(self, context, events): - # Call base method to ensure we do not get recursion. - with catch_drake_warnings(expected_count=1): - LeafSystem.DoPublish(self, context, events) - # N.B. We do not test for a singular call to `DoPublish` - # (checking `assertFalse(self.called_publish)` first) because - # the above `_DeclareInitializationEvent` will call both its - # callback and this event when invoked via - # `Simulator::Initialize` from `call_leaf_system_overrides`, - # even when we explicitly say not to publish at initialize. - self.called_publish = True - def DoCalcTimeDerivatives(self, context, derivatives): # Note: Don't call base method here; it would abort because # derivatives.size() != 0. test.assertEqual(derivatives.get_vector().size(), 2) self.called_continuous = True - def DoCalcDiscreteVariableUpdates( - self, context, events, discrete_state): - # Call base method to ensure we do not get recursion. - with catch_drake_warnings(expected_count=1): - LeafSystem.DoCalcDiscreteVariableUpdates( - self, context, events, discrete_state) - self.called_discrete = True - def DoGetWitnessFunctions(self, context): self.called_getwitness = True return self.getwitness_result @@ -613,15 +580,11 @@ def _system_reset(self, system, context, event, state): self.called_system_reset = True system = TrivialSystem() - self.assertFalse(system.called_publish) self.assertFalse(system.called_continuous) - self.assertFalse(system.called_discrete) self.assertFalse(system.called_initialize) results = call_leaf_system_overrides(system) - self.assertTrue(system.called_publish) self.assertFalse(results["has_direct_feedthrough"]) self.assertTrue(system.called_continuous) - self.assertTrue(system.called_discrete) self.assertTrue(system.called_initialize) self.assertEqual(results["discrete_next_t"], 1.0) @@ -634,7 +597,6 @@ def _system_reset(self, system, context, event, state): system = TrivialSystem() context = system.CreateDefaultContext() system.ForcedPublish(context=context) - self.assertTrue(system.called_publish) self.assertTrue(system.called_forced_publish) context_update = context.Clone() @@ -663,7 +625,6 @@ def _system_reset(self, system, context, event, state): system.CalcForcedDiscreteVariableUpdate( context=context, discrete_state=context_update.get_mutable_discrete_state()) - self.assertTrue(system.called_discrete) self.assertTrue(system.called_forced_discrete) system.CalcForcedUnrestrictedUpdate( diff --git a/common/proto/call_python.h b/common/proto/call_python.h index 46353d48afb8..49e170f4a9c5 100644 --- a/common/proto/call_python.h +++ b/common/proto/call_python.h @@ -2,7 +2,6 @@ #include -#include "drake/common/drake_deprecated.h" #include "drake/common/eigen_types.h" #include "drake/lcmt_call_python.hpp" diff --git a/common/symbolic/trigonometric_polynomial.h b/common/symbolic/trigonometric_polynomial.h index 95ac93d302a5..0c07eadaa13d 100644 --- a/common/symbolic/trigonometric_polynomial.h +++ b/common/symbolic/trigonometric_polynomial.h @@ -5,7 +5,6 @@ #include #include "drake/common/drake_copyable.h" -#include "drake/common/drake_deprecated.h" #include "drake/common/symbolic/expression.h" #include "drake/common/symbolic/rational_function.h" diff --git a/common/trajectories/piecewise_polynomial.h b/common/trajectories/piecewise_polynomial.h index 995165072062..73cb726d8a5e 100644 --- a/common/trajectories/piecewise_polynomial.h +++ b/common/trajectories/piecewise_polynomial.h @@ -9,7 +9,6 @@ #include "drake/common/default_scalars.h" #include "drake/common/drake_copyable.h" -#include "drake/common/drake_deprecated.h" #include "drake/common/eigen_types.h" #include "drake/common/name_value.h" #include "drake/common/polynomial.h" diff --git a/examples/manipulation_station/end_effector_teleop_dualshock4.py b/examples/manipulation_station/end_effector_teleop_dualshock4.py index 9ce43b464bd8..e66d7e848aff 100644 --- a/examples/manipulation_station/end_effector_teleop_dualshock4.py +++ b/examples/manipulation_station/end_effector_teleop_dualshock4.py @@ -171,7 +171,7 @@ def __init__(self, joystick): # Note: This timing affects the keyboard teleop performance. A larger # time step causes more lag in the response. - self.DeclarePeriodicPublishNoHandler(1.0, 0.0) + self.DeclarePeriodicPublishEvent(1.0, 0.0, lambda _: None) self.teleop_manager = TeleopDualShock4Manager(joystick) self.roll = self.pitch = self.yaw = 0 diff --git a/examples/manipulation_station/end_effector_teleop_mouse.py b/examples/manipulation_station/end_effector_teleop_mouse.py index 4cf17730b342..cdd33dec4569 100644 --- a/examples/manipulation_station/end_effector_teleop_mouse.py +++ b/examples/manipulation_station/end_effector_teleop_mouse.py @@ -142,7 +142,7 @@ def __init__(self, grab_focus=True): # Note: This timing affects the keyboard teleop performance. A larger # time step causes more lag in the response. - self.DeclarePeriodicPublishNoHandler(0.01, 0.0) + self.DeclarePeriodicPublishEvent(0.01, 0.0, lambda _: None) self.teleop_manager = TeleopMouseKeyboardManager(grab_focus=grab_focus) self.roll = self.pitch = self.yaw = 0 diff --git a/geometry/optimization/cspace_free_polytope.h b/geometry/optimization/cspace_free_polytope.h index a0f57837562d..e726d73dad7e 100644 --- a/geometry/optimization/cspace_free_polytope.h +++ b/geometry/optimization/cspace_free_polytope.h @@ -11,7 +11,6 @@ #include -#include "drake/common/drake_deprecated.h" #include "drake/geometry/optimization/c_iris_collision_geometry.h" #include "drake/geometry/optimization/cspace_free_polytope_base.h" #include "drake/geometry/optimization/cspace_free_structs.h" diff --git a/geometry/proximity/triangle_surface_mesh.h b/geometry/proximity/triangle_surface_mesh.h index 1b5afeecbaf4..b05f71791620 100644 --- a/geometry/proximity/triangle_surface_mesh.h +++ b/geometry/proximity/triangle_surface_mesh.h @@ -8,7 +8,6 @@ #include "drake/common/drake_assert.h" #include "drake/common/drake_copyable.h" -#include "drake/common/drake_deprecated.h" #include "drake/common/eigen_types.h" #include "drake/geometry/proximity/mesh_traits.h" #include "drake/math/rigid_transform.h" diff --git a/geometry/proximity/volume_mesh.h b/geometry/proximity/volume_mesh.h index 5ca0a2d58faa..aaf64d9caf5a 100644 --- a/geometry/proximity/volume_mesh.h +++ b/geometry/proximity/volume_mesh.h @@ -10,7 +10,6 @@ #include "drake/common/default_scalars.h" #include "drake/common/drake_assert.h" #include "drake/common/drake_copyable.h" -#include "drake/common/drake_deprecated.h" #include "drake/common/eigen_types.h" #include "drake/geometry/proximity/mesh_traits.h" #include "drake/math/linear_solve.h" diff --git a/geometry/query_object.h b/geometry/query_object.h index 93fa8d36c6bb..a8decf810560 100644 --- a/geometry/query_object.h +++ b/geometry/query_object.h @@ -5,7 +5,6 @@ #include #include -#include "drake/common/drake_deprecated.h" #include "drake/geometry/query_results/contact_surface.h" #include "drake/geometry/query_results/deformable_contact.h" #include "drake/geometry/query_results/penetration_as_point_pair.h" diff --git a/geometry/query_results/signed_distance_pair.h b/geometry/query_results/signed_distance_pair.h index ac75d4fca535..a5e3c70ddf92 100644 --- a/geometry/query_results/signed_distance_pair.h +++ b/geometry/query_results/signed_distance_pair.h @@ -3,7 +3,6 @@ #include #include "drake/common/drake_copyable.h" -#include "drake/common/drake_deprecated.h" #include "drake/common/eigen_types.h" #include "drake/geometry/geometry_ids.h" diff --git a/geometry/query_results/signed_distance_to_point.h b/geometry/query_results/signed_distance_to_point.h index 4e809aea2586..332eb309eb35 100644 --- a/geometry/query_results/signed_distance_to_point.h +++ b/geometry/query_results/signed_distance_to_point.h @@ -3,7 +3,6 @@ #include #include "drake/common/drake_copyable.h" -#include "drake/common/drake_deprecated.h" #include "drake/common/eigen_types.h" #include "drake/geometry/geometry_ids.h" diff --git a/geometry/render/render_engine.h b/geometry/render/render_engine.h index e92463063272..c130698a66dc 100644 --- a/geometry/render/render_engine.h +++ b/geometry/render/render_engine.h @@ -10,7 +10,6 @@ #include #include "drake/common/drake_copyable.h" -#include "drake/common/drake_deprecated.h" #include "drake/geometry/geometry_ids.h" #include "drake/geometry/geometry_roles.h" #include "drake/geometry/proximity/volume_mesh.h" diff --git a/geometry/render_gl/internal_render_engine_gl.cc b/geometry/render_gl/internal_render_engine_gl.cc index 8b43fa5766c9..a548ea7aff87 100644 --- a/geometry/render_gl/internal_render_engine_gl.cc +++ b/geometry/render_gl/internal_render_engine_gl.cc @@ -9,7 +9,6 @@ #include #include "drake/common/diagnostic_policy.h" -#include "drake/common/drake_deprecated.h" #include "drake/common/pointer_cast.h" #include "drake/common/scope_exit.h" #include "drake/common/ssize.h" diff --git a/geometry/render_gltf_client/internal_render_engine_gltf_client.cc b/geometry/render_gltf_client/internal_render_engine_gltf_client.cc index e322c5371c93..4999785ca6d4 100644 --- a/geometry/render_gltf_client/internal_render_engine_gltf_client.cc +++ b/geometry/render_gltf_client/internal_render_engine_gltf_client.cc @@ -15,7 +15,6 @@ #include // vtkCommonMath #include // vtkCommonCore -#include "drake/common/drake_deprecated.h" #include "drake/common/never_destroyed.h" #include "drake/common/ssize.h" #include "drake/common/text_logging.h" diff --git a/geometry/scene_graph.h b/geometry/scene_graph.h index 4b44a1e2f351..3700010ac805 100644 --- a/geometry/scene_graph.h +++ b/geometry/scene_graph.h @@ -6,7 +6,6 @@ #include #include -#include "drake/common/drake_deprecated.h" #include "drake/geometry/collision_filter_manager.h" #include "drake/geometry/geometry_frame.h" #include "drake/geometry/geometry_set.h" diff --git a/math/quaternion.h b/math/quaternion.h index ac94a241282b..9fc33e05c604 100644 --- a/math/quaternion.h +++ b/math/quaternion.h @@ -17,7 +17,6 @@ #include "drake/common/drake_assert.h" #include "drake/common/drake_bool.h" -#include "drake/common/drake_deprecated.h" #include "drake/common/eigen_types.h" #include "drake/common/is_approx_equal_abstol.h" #include "drake/math/rotation_matrix.h" diff --git a/multibody/inverse_kinematics/BUILD.bazel b/multibody/inverse_kinematics/BUILD.bazel index 58ff3e13ec86..0f207c1bc1bd 100644 --- a/multibody/inverse_kinematics/BUILD.bazel +++ b/multibody/inverse_kinematics/BUILD.bazel @@ -70,7 +70,6 @@ drake_cc_library( "distance_constraint_utilities.cc", "gaze_target_constraint.cc", "kinematic_evaluator_utilities.cc", - "minimum_distance_constraint.cc", "minimum_distance_lower_bound_constraint.cc", "minimum_distance_upper_bound_constraint.cc", "orientation_constraint.cc", @@ -91,7 +90,6 @@ drake_cc_library( "distance_constraint_utilities.h", "gaze_target_constraint.h", "kinematic_evaluator_utilities.h", - "minimum_distance_constraint.h", "minimum_distance_lower_bound_constraint.h", "minimum_distance_upper_bound_constraint.h", "orientation_constraint.h", diff --git a/multibody/inverse_kinematics/differential_inverse_kinematics.h b/multibody/inverse_kinematics/differential_inverse_kinematics.h index 41680a40fd6e..29e6fad86472 100644 --- a/multibody/inverse_kinematics/differential_inverse_kinematics.h +++ b/multibody/inverse_kinematics/differential_inverse_kinematics.h @@ -11,7 +11,6 @@ #include "drake/common/copyable_unique_ptr.h" #include "drake/common/drake_copyable.h" -#include "drake/common/drake_deprecated.h" #include "drake/common/eigen_types.h" #include "drake/common/fmt_ostream.h" #include "drake/math/rigid_transform.h" diff --git a/multibody/inverse_kinematics/inverse_kinematics.cc b/multibody/inverse_kinematics/inverse_kinematics.cc index bfc8fbb45bff..dd603a5b66b5 100644 --- a/multibody/inverse_kinematics/inverse_kinematics.cc +++ b/multibody/inverse_kinematics/inverse_kinematics.cc @@ -7,7 +7,6 @@ #include "drake/multibody/inverse_kinematics/angle_between_vectors_cost.h" #include "drake/multibody/inverse_kinematics/distance_constraint.h" #include "drake/multibody/inverse_kinematics/gaze_target_constraint.h" -#include "drake/multibody/inverse_kinematics/minimum_distance_constraint.h" #include "drake/multibody/inverse_kinematics/minimum_distance_lower_bound_constraint.h" #include "drake/multibody/inverse_kinematics/minimum_distance_upper_bound_constraint.h" #include "drake/multibody/inverse_kinematics/orientation_constraint.h" @@ -196,19 +195,6 @@ solvers::Binding InverseKinematics::AddAngleBetweenVectorsCost( return prog_->AddCost(cost, q_); } -#pragma GCC diagnostic push -#pragma GCC diagnostic ignored "-Wdeprecated-declarations" -solvers::Binding -InverseKinematics::AddMinimumDistanceConstraint( - double minimum_distance, double influence_distance_offset) { - auto constraint = - std::shared_ptr(new MinimumDistanceConstraint( - &plant_, minimum_distance, get_mutable_context(), {}, - influence_distance_offset)); - return prog_->AddConstraint(constraint, q_); -} -#pragma GCC diagnostic pop - solvers::Binding InverseKinematics::AddMinimumDistanceLowerBoundConstraint( double bound, double influence_distance_offset) { diff --git a/multibody/inverse_kinematics/inverse_kinematics.h b/multibody/inverse_kinematics/inverse_kinematics.h index 3194ddeee9f9..1b6ed6900cc0 100644 --- a/multibody/inverse_kinematics/inverse_kinematics.h +++ b/multibody/inverse_kinematics/inverse_kinematics.h @@ -281,37 +281,6 @@ class InverseKinematics { const Frame& frameB, const Eigen::Ref& nb_B, double c); - // TODO(hongkai.dai): remove this documentation. - /** - * Adds the constraint that the pairwise distance between objects should be no - * smaller than `minimum_distance`. We consider the distance between pairs - * of - * 1. Anchored (static) object and a dynamic object. - * 2. A dynamic object and another dynamic object, if one is not the parent - * link of the other. - * @param minimum_distance The minimum allowed value, dₘᵢₙ, of the signed - * distance between any candidate pair of geometries. - * @param influence_distance_offset The difference (in meters) between the - * influence distance, d_influence, and the minimum distance, dₘᵢₙ. This value - * must be finite and strictly positive, as it is used to scale the signed - * distances between pairs of geometries. Smaller values may improve - * performance, as fewer pairs of geometries need to be considered in each - * constraint evaluation. @default 1 meter - * @see MinimumDistanceConstraint for more details on the constraint - * formulation. - * @pre The MultibodyPlant passed to the constructor of `this` has registered - * its geometry with a SceneGraph. - * @pre 0 < `influence_distance_offset` < ∞ - */ - DRAKE_DEPRECATED("2024-02-01", - "Use AddMinimumDistanceLowerBoundConstraint() instead. The " - "default value for influence_distance_offset has *changed*. " - "It changes from 1 m to 0.01 m. If you're relying on the " - "1 m default value, make sure to pass that value explicitly " - "when calling AddMinimumDistanceLowerBoundConstraint().") - solvers::Binding AddMinimumDistanceConstraint( - double minimum_distance, double influence_distance_offset = 1); - /** * Adds the constraint that the pairwise distance between objects should be no * smaller than `bound`. We consider the distance between diff --git a/multibody/inverse_kinematics/minimum_distance_constraint.cc b/multibody/inverse_kinematics/minimum_distance_constraint.cc deleted file mode 100644 index bdec36fe034a..000000000000 --- a/multibody/inverse_kinematics/minimum_distance_constraint.cc +++ /dev/null @@ -1,246 +0,0 @@ -#include "drake/multibody/inverse_kinematics/minimum_distance_constraint.h" - -#include -#include - -#include - -#include "drake/multibody/inverse_kinematics/distance_constraint_utilities.h" -#include "drake/multibody/inverse_kinematics/kinematic_evaluator_utilities.h" - -namespace drake { -namespace multibody { -using internal::RefFromPtrOrThrow; - -namespace { -const double kInf = std::numeric_limits::infinity(); - -int NumConstraints(double minimum_distance_lower, - double minimum_distance_upper) { - return static_cast(std::isfinite(minimum_distance_lower)) + - static_cast(std::isfinite(minimum_distance_upper)); -} -} // namespace - -void MinimumDistanceConstraint::CheckMinimumDistanceBounds( - double minimum_distance_lower, double minimum_distance_upper, - double influence_distance) const { - if (!std::isfinite(influence_distance)) { - throw std::invalid_argument( - "MinimumDistanceConstraint: influence_distance must be finite."); - } - if (std::isnan(minimum_distance_lower) || - influence_distance <= minimum_distance_lower) { - throw std::invalid_argument(fmt::format( - "MinimumDistanceConstraint: influence_distance={}, must be " - "larger than minimum_distance_lower={}; equivalently, " - "influence_distance_offset={}, but it needs to be positive.", - influence_distance, minimum_distance_lower, - influence_distance - minimum_distance_lower)); - } - if (std::isfinite(minimum_distance_upper) && - influence_distance <= minimum_distance_upper) { - throw std::invalid_argument(fmt::format( - "MinimumDistanceConstraint: influence_distance={}, must be larger than " - "minimum_distance_upper={}.", - influence_distance, minimum_distance_upper)); - } -} - -template -void MinimumDistanceConstraint::Initialize( - const MultibodyPlant& plant, systems::Context* plant_context, - double minimum_distance_lower, double minimum_distance_upper, - double influence_distance, - solvers::MinimumValuePenaltyFunction penalty_function) { - CheckPlantIsConnectedToSceneGraph(plant, *plant_context); - CheckMinimumDistanceBounds(minimum_distance_lower, minimum_distance_upper, - influence_distance); - const auto& query_port = plant.get_geometry_query_input_port(); - // Maximum number of SignedDistancePairs returned by calls to - // ComputeSignedDistancePairwiseClosestPoints(). - const int num_collision_candidates = - query_port.template Eval>(*plant_context) - .inspector() - .GetCollisionCandidates() - .size(); -#pragma GCC diagnostic push -#pragma GCC diagnostic ignored "-Wdeprecated-declarations" - minimum_value_constraint_ = std::make_unique( - this->num_vars(), minimum_distance_lower, minimum_distance_upper, - influence_distance, num_collision_candidates, - [&plant, plant_context](const auto& x, double influence_distance_val) { - return internal::Distances(plant, plant_context, x, - influence_distance_val); - }, - [&plant, plant_context](const auto& x, double influence_distance_val) { - return internal::Distances(plant, plant_context, x, - influence_distance_val); - }); -#pragma GCC diagnostic pop - this->set_bounds(minimum_value_constraint_->lower_bound(), - minimum_value_constraint_->upper_bound()); - if (penalty_function) { - minimum_value_constraint_->set_penalty_function(penalty_function); - } -} - -void MinimumDistanceConstraint::Initialize( - const planning::CollisionChecker& collision_checker, - planning::CollisionCheckerContext* collision_checker_context, - double minimum_distance_lower, double minimum_distance_upper, - double influence_distance, - solvers::MinimumValuePenaltyFunction penalty_function) { - CheckMinimumDistanceBounds(minimum_distance_lower, minimum_distance_upper, - influence_distance); -#pragma GCC diagnostic push -#pragma GCC diagnostic ignored "-Wdeprecated-declarations" - minimum_value_constraint_ = std::make_unique( - collision_checker.plant().num_positions(), minimum_distance_lower, - minimum_distance_upper, influence_distance, - collision_checker.MaxContextNumDistances(*collision_checker_context), - [this](const Eigen::Ref& x, - double influence_distance_val) { - return internal::Distances(*(this->collision_checker_), - this->collision_checker_context_, x, - influence_distance_val); - }, - [this](const Eigen::Ref& x, - double influence_distance_val) { - return internal::Distances(*(this->collision_checker_), - this->collision_checker_context_, x, - influence_distance_val); - }); -#pragma GCC diagnostic pop - this->set_bounds(minimum_value_constraint_->lower_bound(), - minimum_value_constraint_->upper_bound()); - if (penalty_function) { - minimum_value_constraint_->set_penalty_function(penalty_function); - } -} - -MinimumDistanceConstraint::MinimumDistanceConstraint( - const multibody::MultibodyPlant* const plant, - double minimum_distance, systems::Context* plant_context, - solvers::MinimumValuePenaltyFunction penalty_function, - double influence_distance_offset) - : MinimumDistanceConstraint(plant, minimum_distance, - kInf /* minimum_distance_upper */, - plant_context, penalty_function, - influence_distance_offset + minimum_distance) {} - -MinimumDistanceConstraint::MinimumDistanceConstraint( - const multibody::MultibodyPlant* const plant, - double minimum_distance_lower, double minimum_distance_upper, - systems::Context* plant_context, - solvers::MinimumValuePenaltyFunction penalty_function, - double influence_distance_offset) - : solvers::Constraint( - NumConstraints(minimum_distance_lower, minimum_distance_upper), - RefFromPtrOrThrow(plant).num_positions(), - Eigen::VectorXd::Zero( - NumConstraints(minimum_distance_lower, minimum_distance_upper)), - Eigen::VectorXd::Zero( - NumConstraints(minimum_distance_lower, minimum_distance_upper))), - /* The lower and upper bounds will be set to correct value later in - Initialize() function */ - plant_double_{plant}, - plant_context_double_{plant_context}, - plant_autodiff_{nullptr}, - plant_context_autodiff_{nullptr}, - collision_checker_{nullptr} { - Initialize(*plant_double_, plant_context_double_, minimum_distance_lower, - minimum_distance_upper, influence_distance_offset, - penalty_function); -} - -MinimumDistanceConstraint::MinimumDistanceConstraint( - const multibody::MultibodyPlant* const plant, - double minimum_distance, systems::Context* plant_context, - solvers::MinimumValuePenaltyFunction penalty_function, - double influence_distance_offset) - : MinimumDistanceConstraint(plant, minimum_distance, - kInf /* minimum_distance_upper */, - plant_context, penalty_function, - influence_distance_offset + minimum_distance) {} - -MinimumDistanceConstraint::MinimumDistanceConstraint( - const multibody::MultibodyPlant* const plant, - double minimum_distance_lower, double minimum_distance_upper, - systems::Context* plant_context, - solvers::MinimumValuePenaltyFunction penalty_function, - double influence_distance) - : solvers::Constraint( - NumConstraints(minimum_distance_lower, minimum_distance_upper), - RefFromPtrOrThrow(plant).num_positions(), - Eigen::VectorXd::Zero( - NumConstraints(minimum_distance_lower, minimum_distance_upper)), - Eigen::VectorXd::Zero( - NumConstraints(minimum_distance_lower, minimum_distance_upper))), - plant_double_{nullptr}, - plant_context_double_{nullptr}, - plant_autodiff_{plant}, - plant_context_autodiff_{plant_context}, - collision_checker_{nullptr} { - Initialize(*plant_autodiff_, plant_context_autodiff_, minimum_distance_lower, - minimum_distance_upper, influence_distance, penalty_function); -} - -MinimumDistanceConstraint::MinimumDistanceConstraint( - const planning::CollisionChecker* collision_checker, - double minimum_distance_lower, - planning::CollisionCheckerContext* collision_checker_context, - solvers::MinimumValuePenaltyFunction penalty_function, - double influence_distance_offset) - : MinimumDistanceConstraint( - collision_checker, minimum_distance_lower, - kInf /* minimum_distance_upper */, collision_checker_context, - penalty_function, - minimum_distance_lower + influence_distance_offset) {} - -MinimumDistanceConstraint::MinimumDistanceConstraint( - const planning::CollisionChecker* collision_checker, - double minimum_distance_lower, double minimum_distance_upper, - planning::CollisionCheckerContext* collision_checker_context, - solvers::MinimumValuePenaltyFunction penalty_function, - double influence_distance) - : solvers::Constraint( - NumConstraints(minimum_distance_lower, minimum_distance_upper), - internal::PtrOrThrow( - collision_checker, - "MinimumDistanceConstraint: collision_checker is nullptr") - ->plant() - .num_positions(), - Eigen::VectorXd::Zero( - NumConstraints(minimum_distance_lower, minimum_distance_upper)), - Eigen::VectorXd::Zero( - NumConstraints(minimum_distance_lower, minimum_distance_upper))), - plant_double_{nullptr}, - plant_context_double_{nullptr}, - plant_autodiff_{nullptr}, - plant_context_autodiff_{nullptr}, - collision_checker_{collision_checker}, - collision_checker_context_{collision_checker_context} { - Initialize(*collision_checker_, collision_checker_context_, - minimum_distance_lower, minimum_distance_upper, influence_distance, - penalty_function); -} - -template -void MinimumDistanceConstraint::DoEvalGeneric( - const Eigen::Ref>& x, VectorX* y) const { - minimum_value_constraint_->Eval(x, y); -} - -void MinimumDistanceConstraint::DoEval( - const Eigen::Ref& x, Eigen::VectorXd* y) const { - DoEvalGeneric(x, y); -} - -void MinimumDistanceConstraint::DoEval(const Eigen::Ref& x, - AutoDiffVecXd* y) const { - DoEvalGeneric(x, y); -} - -} // namespace multibody -} // namespace drake diff --git a/multibody/inverse_kinematics/minimum_distance_constraint.h b/multibody/inverse_kinematics/minimum_distance_constraint.h deleted file mode 100644 index 6a2ebb18e089..000000000000 --- a/multibody/inverse_kinematics/minimum_distance_constraint.h +++ /dev/null @@ -1,258 +0,0 @@ -#pragma once - -#include -#include - -#include "drake/multibody/plant/multibody_plant.h" -#include "drake/planning/collision_checker.h" -#include "drake/solvers/constraint.h" -#include "drake/solvers/minimum_value_constraint.h" -#include "drake/systems/framework/context.h" - -namespace drake { -namespace multibody { - -/** Computes the penalty function φ(x) and its derivatives dφ(x)/dx. Valid -penalty functions must meet the following criteria: - -1. φ(x) ≥ 0 ∀ x ∈ ℝ. -2. dφ(x)/dx ≤ 0 ∀ x ∈ ℝ. -3. φ(x) = 0 ∀ x ≥ 0. -4. dφ(x)/dx < 0 ∀ x < 0. */ -using MinimumDistancePenaltyFunction DRAKE_DEPRECATED( - "2024-02-01", "Use solvers::MinimumValuePenaltyFunction.") = - solvers::MinimumValuePenaltyFunction; - -/** A hinge loss function smoothed by exponential function. This loss -function is differentiable everywhere. The formulation is described in -section II.C of [2]. -The penalty is -
-       ⎧ 0            if x ≥ 0
-φ(x) = ⎨
-       ⎩  -x exp(1/x) if x < 0.
-
-[2] "Whole-body Motion Planning with Centroidal Dynamics and Full -Kinematics" by Hongkai Dai, Andres Valenzuela and Russ Tedrake, IEEE-RAS -International Conference on Humanoid Robots, 2014. */ -using solvers::ExponentiallySmoothedHingeLoss; - -/** A linear hinge loss, smoothed with a quadratic loss near the origin. The -formulation is in equation (6) of [1]. -The penalty is -
-       ⎧  0        if x ≥ 0
-φ(x) = ⎨  x²/2     if -1 < x < 0
-       ⎩  -0.5 - x if x ≤ -1.
-
-[1] "Loss Functions for Preference Levels: Regression with Discrete Ordered -Labels." by Jason Rennie and Nathan Srebro, Proceedings of IJCAI -multidisciplinary workshop on Advances in Preference Handling. */ -using solvers::QuadraticallySmoothedHingeLoss; - -/** Constrain lb <= min(d) <= ub, namely the signed distance between all -candidate pairs of geometries (according to the logic of -SceneGraphInspector::GetCollisionCandidates()) to be no smaller than a specified -minimum distance lb, and the minimal distance is no larger than a specified ub. -This constraint should be bound to decision variables corresponding to the -configuration vector, q, of the associated MultibodyPlant. - -The formulation of the constraint is - - SmoothOverMax( φ((dᵢ(q) - d_influence)/(d_influence - lb)) / φ(-1) ) ≤ 1 - SmoothUnderMax( φ((dᵢ(q) - d_influence)/(d_influence - ub)) / φ(-1) ) ≥ 1 - -where dᵢ(q) is the signed distance of the i-th pair, lb is the minimum -allowable distance, d_influence is the "influence distance" (the distance below -which a pair of geometries influences the constraint), φ is a -solvers::MinimumValuePenaltyFunction. SmoothOverMax(d) and -SmoothUnderMax(d) is smooth over and under approximation of max(d). We require -that lb < d_influence. The input scaling (dᵢ(q) - d_influence)/(d_influence - -lb) ensures that at the boundary of the feasible set (when dᵢ(q) == lb), we -evaluate the penalty function at -1, where it is required to have a non-zero -gradient. - -@ingroup solver_evaluators -*/ -class DRAKE_DEPRECATED( - "2024-02-01", - "Use MinimumDistanceLowerBoundConstraint if you want the smallest distance " - "to be lower bounded, or MinimumDistanceUpperBoundConstraint if you want " - "the smallest distance to be upper bounded.") - MinimumDistanceConstraint final : public solvers::Constraint { - public: - DRAKE_NO_COPY_NO_MOVE_NO_ASSIGN(MinimumDistanceConstraint) - - /** Constructs a MinimumDistanceConstraint. - @param plant The multibody system on which the constraint will be evaluated. - @param minimum_distance The minimum allowed value, lb, of the signed - distance between any candidate pair of geometries. - @param penalty_function The penalty function formulation. - @default QuadraticallySmoothedHinge - @param influence_distance_offset The difference (in meters) between the - influence distance, d_influence, and the minimum distance, lb (see class - documentation), namely influence_distance = minimum_distance_lower + - influence_distance_offset. This value must be finite and strictly positive, as - it is used to scale the signed distances between pairs of geometries. Smaller - values may improve performance, as fewer pairs of geometries need to be - considered in each constraint evaluation. @default 1 meter. - The chosen influence_distance_offset can significantly affect the runtime and - optimization performance of using this constraint. Larger values result in - more expensive collision checks (since more potential collision candidates - must be considered) and may result in worse optimization performance (the - optimizer may not be able to find a configuration that satisfies the - constraint). In work at TRI, we have used much lower values (e.g. 1e-6) for - influence_distance_offset with good results. - @throws std::exception if `plant` has not registered its geometry with - a SceneGraph object. - @throws std::exception if influence_distance_offset = ∞. - @throws std::exception if influence_distance_offset ≤ 0. - @pydrake_mkdoc_identifier{double_no_upper_bound} - */ - MinimumDistanceConstraint( - const multibody::MultibodyPlant* const plant, - double minimum_distance, systems::Context* plant_context, - solvers::MinimumValuePenaltyFunction penalty_function = {}, - double influence_distance_offset = 1); - - /** - Overloaded constructor. lower <= min(distance) <= upper. - @param minimum_distance_lower The lower bound of the minimum distance. lower - <= min(distance). - @param minimum_distance_upper The upper bound of the minimum distance. - min(distance) <= upper. If minimum_distance_upper is finite, then it must be - smaller than influence_distance_offset. - @pydrake_mkdoc_identifier{double_with_upper_bound} - */ - MinimumDistanceConstraint( - const multibody::MultibodyPlant* const plant, - double minimum_distance_lower, double minimum_distance_upper, - systems::Context* plant_context, - solvers::MinimumValuePenaltyFunction penalty_function, - double influence_distance); - - /** - Overloaded constructor. - Constructs the constraint using MultibodyPlant. - @pydrake_mkdoc_identifier{autodiff_no_upper_bound} - */ - MinimumDistanceConstraint( - const multibody::MultibodyPlant* const plant, - double minimum_distance, systems::Context* plant_context, - solvers::MinimumValuePenaltyFunction penalty_function = {}, - double influence_distance_offset = 1); - - /** - Overloaded constructor. - Constructs the constraint using MultibodyPlant. lower <= - min(distance) <= upper. - @param minimum_distance_lower The lower bound of the minimum distance. lower - <= min(distance). We must have minimum_distance_lower <= influence_distance. - @param minimum_distance_upper The upper bound of the minimum distance. - min(distance) <= upper. If minimum_distance_upper is finite, then it must be - smaller than influence_distance. - @param collision_checker_context The context for the collision checker. - @pydrake_mkdoc_identifier{autodiff_with_upper_bound} - */ - MinimumDistanceConstraint( - const multibody::MultibodyPlant* const plant, - double minimum_distance_lower, double minimum_distance_upper, - systems::Context* plant_context, - solvers::MinimumValuePenaltyFunction penalty_function, - double influence_distance); - - /** Overloaded constructor. - Constructs the constraint with CollisionChecker instead of MultibodyPlant. - @param collision_checker collision_checker must outlive this constraint. - @param collision_checker_context The context for the collision checker. See - CollisionChecker class for more details. - @pydrake_mkdoc_identifier{collision_checker_no_upper_bound} - */ - MinimumDistanceConstraint( - const planning::CollisionChecker* collision_checker, - double minimum_distance, - planning::CollisionCheckerContext* collision_checker_context, - solvers::MinimumValuePenaltyFunction penalty_function = {}, - double influence_distance_offset = 1); - - /** Overloaded constructor. - Constructs the constraint with CollisionChecker instead of MultibodyPlant. - @param collision_checker collision_checker must outlive this constraint. - @param collision_checker_context The context for the collision checker. See - CollisionChecker class for more details. - @pydrake_mkdoc_identifier{collision_checker_with_upper_bound} - */ - MinimumDistanceConstraint( - const planning::CollisionChecker* collision_checker, - double minimum_distance_lower, double minimum_distance_upper, - planning::CollisionCheckerContext* collision_checker_context, - solvers::MinimumValuePenaltyFunction penalty_function, - double influence_distance); - - ~MinimumDistanceConstraint() override {} - - /** Getter for the lower bound of the minimum distance. */ - double minimum_distance_lower() const { - return minimum_value_constraint_->minimum_value_lower(); - } - - /** Getter for the upper bound of the minimum distance. */ - double minimum_distance_upper() const { - return minimum_value_constraint_->minimum_value_upper(); - } - - /** Getter for the influence distance. */ - double influence_distance() const { - return minimum_value_constraint_->influence_value(); - } - - private: - void DoEval(const Eigen::Ref& x, - Eigen::VectorXd* y) const override; - - void DoEval(const Eigen::Ref& x, - AutoDiffVecXd* y) const override; - - void DoEval(const Eigen::Ref>&, - VectorX*) const override { - throw std::logic_error( - "MinimumDistanceConstraint::DoEval() does not work for symbolic " - "variables."); - } - - template - void DoEvalGeneric(const Eigen::Ref>& x, - VectorX* y) const; - - template - void Initialize(const MultibodyPlant& plant, - systems::Context* plant_context, - double minimum_distance_lower, double minimum_distance_upper, - double influence_distance, - solvers::MinimumValuePenaltyFunction penalty_function); - - // Overload Initialize with CollisionChecker instead of MultibodyPlant. - void Initialize(const planning::CollisionChecker& collision_checker, - planning::CollisionCheckerContext* collision_checker_context, - double minimum_distance_lower, double minimum_distance_upper, - double influence_distance, - solvers::MinimumValuePenaltyFunction penalty_function); - - void CheckMinimumDistanceBounds(double minimum_distance_lower, - double minimum_distance_upper, - double influence_distance) const; - - const multibody::MultibodyPlant* const plant_double_; - systems::Context* const plant_context_double_; -#pragma GCC diagnostic push -#pragma GCC diagnostic ignored "-Wdeprecated-declarations" - std::unique_ptr minimum_value_constraint_; -#pragma GCC diagnostic pop - const multibody::MultibodyPlant* const plant_autodiff_; - systems::Context* const plant_context_autodiff_; - - const planning::CollisionChecker* collision_checker_; - planning::CollisionCheckerContext* collision_checker_context_; -}; -} // namespace multibody -} // namespace drake diff --git a/multibody/inverse_kinematics/test/inverse_kinematics_test.cc b/multibody/inverse_kinematics/test/inverse_kinematics_test.cc index bb69a41dff45..b1df18887bdb 100644 --- a/multibody/inverse_kinematics/test/inverse_kinematics_test.cc +++ b/multibody/inverse_kinematics/test/inverse_kinematics_test.cc @@ -533,58 +533,6 @@ TEST_F(TwoFreeBodiesTest, PolyhedronConstraint) { } } -#pragma GCC diagnostic push -#pragma GCC diagnostic ignored "-Wdeprecated-declarations" -TEST_F(TwoFreeSpheresTest, MinimumDistanceConstraintTest) { - const double min_distance = 0.1; - - InverseKinematics ik(*plant_double_, plant_context_double_); - - auto constraint = ik.AddMinimumDistanceConstraint(min_distance); - - // The two spheres are colliding in the initial guess. - ik.get_mutable_prog()->SetInitialGuess(ik.q().head<4>(), - Eigen::Vector4d(1, 0, 0, 0)); - ik.get_mutable_prog()->SetInitialGuess(ik.q().segment<3>(4), - Eigen::Vector3d(0, 0, 0.01)); - ik.get_mutable_prog()->SetInitialGuess(ik.q().segment<4>(7), - Eigen::Vector4d(1, 0, 0, 0)); - ik.get_mutable_prog()->SetInitialGuess(ik.q().tail<3>(), - Eigen::Vector3d(0, 0, -0.01)); - - auto solve_and_check = [&]() { - const solvers::MathematicalProgramResult result = Solve(ik.prog()); - EXPECT_TRUE(result.is_success()); - - const Eigen::Vector3d p_WB1 = result.GetSolution(ik.q().segment<3>(4)); - const Eigen::Quaterniond quat_WB1( - result.GetSolution(ik.q()(0)), result.GetSolution(ik.q()(1)), - result.GetSolution(ik.q()(2)), result.GetSolution(ik.q()(3))); - const Eigen::Vector3d p_WB2 = result.GetSolution(ik.q().tail<3>()); - const Eigen::Quaterniond quat_WB2( - result.GetSolution(ik.q()(7)), result.GetSolution(ik.q()(8)), - result.GetSolution(ik.q()(9)), result.GetSolution(ik.q()(10))); - const Eigen::Vector3d p_WS1 = - p_WB1 + quat_WB1.toRotationMatrix() * X_B1S1_.translation(); - const Eigen::Vector3d p_WS2 = - p_WB2 + quat_WB2.toRotationMatrix() * X_B2S2_.translation(); - // This large error is due to the derivative of the penalty function(i.e., - // the gradient ∂penalty/∂distance) being small near minimum_distance. Hence - // a small violation on the penalty leads to a large violation on the - // minimum_distance. - const double tol = 2e-4; - EXPECT_GE((p_WS1 - p_WS2).norm() - radius1_ - radius2_, min_distance - tol); - }; - - solve_and_check(); - - // Now set the two spheres to coincide at the initial guess, and solve again. - ik.get_mutable_prog()->SetInitialGuess( - ik.q().tail<3>(), ik.prog().initial_guess().segment<3>(4)); - solve_and_check(); -} -#pragma GCC diagnostic pop - TEST_F(TwoFreeSpheresTest, MinimumDistanceLowerBoundConstraintTest) { const double min_distance_lower = 0.1; diff --git a/multibody/inverse_kinematics/test/minimum_distance_constraint_test.cc b/multibody/inverse_kinematics/test/minimum_distance_constraint_test.cc index 85daface0e2f..2835219857c7 100644 --- a/multibody/inverse_kinematics/test/minimum_distance_constraint_test.cc +++ b/multibody/inverse_kinematics/test/minimum_distance_constraint_test.cc @@ -1,5 +1,3 @@ -#include "drake/multibody/inverse_kinematics/minimum_distance_constraint.h" - #include #include "drake/common/test_utilities/expect_throws_message.h" @@ -34,41 +32,6 @@ Vector3 ComputeCollisionSphereCenterPosition( class TwoFreeSpheresMinimumDistanceTest : public TwoFreeSpheresTest { public: -#pragma GCC diagnostic push -#pragma GCC diagnostic ignored "-Wdeprecated-declarations" - void CheckConstraintBounds( - const MinimumDistanceConstraint& constraint) const { - int num_constraints = 0; - std::vector lower_bound_expected; - std::vector upper_bound_expected; - if (std::isfinite(constraint.minimum_distance_lower())) { - // Impose the constraint - // SmoothOverMax( φ((dᵢ(q) - d_influence)/(d_influence - lb)) / φ(-1) ) ≤ - // 1 - num_constraints++; - lower_bound_expected.push_back(-kInf); - upper_bound_expected.push_back(1); - } - if (std::isfinite(constraint.minimum_distance_upper())) { - // Impose the constraint - // SmoothUnderMax( φ((dᵢ(q) - d_influence)/(d_influence - ub)) / φ(-1) ) ≥ - // 1 - num_constraints++; - lower_bound_expected.push_back(1); - upper_bound_expected.push_back(kInf); - } - EXPECT_EQ(constraint.num_constraints(), num_constraints); - EXPECT_TRUE(CompareMatrices( - constraint.lower_bound(), - Eigen::Map(lower_bound_expected.data(), - lower_bound_expected.size()))); - EXPECT_TRUE(CompareMatrices( - constraint.upper_bound(), - Eigen::Map(upper_bound_expected.data(), - upper_bound_expected.size()))); - } -#pragma GCC diagnostic pop - void CheckConstraintBounds( const MinimumDistanceLowerBoundConstraint& constraint) const { EXPECT_EQ(constraint.num_constraints(), 1); @@ -125,32 +88,6 @@ class TwoFreeSpheresMinimumDistanceTest : public TwoFreeSpheresTest { CheckConstraintEvalNonsymbolic(constraint, q_autodiff, 1E-12); } -#pragma GCC diagnostic push -#pragma GCC diagnostic ignored "-Wdeprecated-declarations" - void CheckConstraintEvalBetweenMinimumUpperAndInfluenceDistance( - const MinimumDistanceConstraint& constraint, const Eigen::Vector3d& p_WB1, - const Eigen::Vector3d p_WB2) const { - DRAKE_DEMAND(std::isfinite(constraint.minimum_distance_lower())); - DRAKE_DEMAND(std::isfinite(constraint.minimum_distance_upper())); - Eigen::Matrix q; - Eigen::Matrix q_autodiff; - ConstructQ(p_WB1, p_WB2, &q, &q_autodiff); - Eigen::VectorXd y_double(constraint.num_constraints()); - constraint.Eval(q, &y_double); - AutoDiffVecXd y_autodiff(constraint.num_constraints()); - constraint.Eval(q_autodiff, &y_autodiff); - - EXPECT_FALSE(constraint.CheckSatisfied(q)); - EXPECT_FALSE(constraint.CheckSatisfied(q_autodiff)); - // Check that the value is strictly greater than 0. - EXPECT_GE(y_double(0), constraint.lower_bound()(0)); - EXPECT_LE(y_double(0), constraint.upper_bound()(0)); - EXPECT_FALSE(y_double(1) >= constraint.lower_bound()(1) && - y_double(1) <= constraint.upper_bound()(1)); - CheckConstraintEvalNonsymbolic(constraint, q_autodiff, 1E-12); - } -#pragma GCC diagnostic pop - void CheckConstraintEvalBetweenMinimumUpperAndInfluenceDistance( const MinimumDistanceUpperBoundConstraint& constraint, const Eigen::Vector3d& p_WB1, const Eigen::Vector3d& p_WB2) const { @@ -169,27 +106,6 @@ class TwoFreeSpheresMinimumDistanceTest : public TwoFreeSpheresTest { CheckConstraintEvalNonsymbolic(constraint, q_autodiff, 1E-12); } -#pragma GCC diagnostic push -#pragma GCC diagnostic ignored "-Wdeprecated-declarations" - void CheckConstraintEvalBetweenMinimumLowerAndUpperDistance( - const MinimumDistanceConstraint& constraint, const Eigen::Vector3d& p_WB1, - const Eigen::Vector3d& p_WB2) const { - DRAKE_DEMAND(std::isfinite(constraint.minimum_distance_lower())); - DRAKE_DEMAND(std::isfinite(constraint.minimum_distance_upper())); - Eigen::Matrix q; - Eigen::Matrix q_autodiff; - ConstructQ(p_WB1, p_WB2, &q, &q_autodiff); - Eigen::VectorXd y_double(constraint.num_constraints()); - constraint.Eval(q, &y_double); - AutoDiffVecXd y_autodiff(constraint.num_constraints()); - constraint.Eval(q_autodiff, &y_autodiff); - - EXPECT_TRUE(constraint.CheckSatisfied(q)); - EXPECT_TRUE(constraint.CheckSatisfied(q_autodiff)); - CheckConstraintEvalNonsymbolic(constraint, q_autodiff, 1E-12); - } -#pragma GCC diagnostic pop - void CheckConstraintEvalBetweenMinimumLowerAndInfluenceDistance( const MinimumDistanceLowerBoundConstraint& constraint, const Eigen::Vector3d& p_WB1, const Eigen::Vector3d& p_WB2) const { @@ -207,29 +123,6 @@ class TwoFreeSpheresMinimumDistanceTest : public TwoFreeSpheresTest { CheckConstraintEvalNonsymbolic(constraint, q_autodiff, 1E-12); } -#pragma GCC diagnostic push -#pragma GCC diagnostic ignored "-Wdeprecated-declarations" - void CheckConstraintEvalSmallerThanMinimumLowerDistance( - const MinimumDistanceConstraint& constraint, const Eigen::Vector3d& p_WB1, - const Eigen::Vector3d& p_WB2) const { - const Eigen::Quaterniond sphere1_quaternion(1, 0, 0, 0); - const Eigen::Quaterniond sphere2_quaternion(1, 0, 0, 0); - Eigen::Matrix q; - q << QuaternionToVectorWxyz(sphere1_quaternion), p_WB1, - QuaternionToVectorWxyz(sphere2_quaternion), p_WB2; - Eigen::VectorXd y_double(constraint.num_constraints()); - constraint.Eval(q, &y_double); - Eigen::Matrix q_autodiff = - math::InitializeAutoDiff(q); - AutoDiffVecXd y_autodiff(constraint.num_constraints()); - constraint.Eval(q_autodiff, &y_autodiff); - - EXPECT_FALSE(constraint.CheckSatisfied(q)); - EXPECT_FALSE(constraint.CheckSatisfied(q_autodiff)); - CheckConstraintEvalNonsymbolic(constraint, q_autodiff, 1E-12); - } -#pragma GCC diagnostic pop - void CheckConstraintEvalSmallerThanMinimumLowerDistance( const MinimumDistanceLowerBoundConstraint& constraint, const Eigen::Vector3d& p_WB1, const Eigen::Vector3d& p_WB2) const { @@ -262,51 +155,6 @@ class TwoFreeSpheresMinimumDistanceTest : public TwoFreeSpheresTest { CheckConstraintEvalNonsymbolic(constraint, q_autodiff, 1E-12); } -#pragma GCC diagnostic push -#pragma GCC diagnostic ignored "-Wdeprecated-declarations" - void CheckConstraintEval(const MinimumDistanceConstraint& constraint) { - // Distance between the spheres is larger than influence_distance - Eigen::Vector3d p_WB1(0.2, 1.2, 0.3); - Eigen::Vector3d p_WB2(1.2, -0.4, 2.3); - CheckConstraintEvalLargerThanInfluenceDistance( - constraint, p_WB1, p_WB2, false /* expect satisfied */); - - // Distance between the spheres is larger than minimum_distance_upper but - // less than influence distance - p_WB1 << 0.2, 1.2, 0.3; - p_WB2 = p_WB1 + Eigen::Vector3d(1.0 / 3, 2.0 / 3, 2.0 / 3) * - (radius1_ + radius2_ + - 0.5 * (constraint.minimum_distance_upper() + - constraint.influence_distance())); - - // Distance between the spheres is larger than minimum_distance_lower - // but less than minimum_distance_upper - p_WB1 << 0.1, 0.2, 0.3; - p_WB2 = p_WB1 + Eigen::Vector3d(1.0 / 3, 2.0 / 3, 2.0 / 3) * - (radius1_ + radius2_ + - 0.5 * (constraint.minimum_distance_lower() + - constraint.minimum_distance_upper())); - CheckConstraintEvalBetweenMinimumLowerAndUpperDistance(constraint, p_WB1, - p_WB2); - - // Two spheres are colliding. - p_WB1 << 0.1, 0.2, 0.3; - p_WB2 << 0.11, 0.21, 0.31; - CheckConstraintEvalSmallerThanMinimumLowerDistance(constraint, p_WB1, - p_WB2); - - // Two spheres are separated, but their distance is smaller than - // minimum_distance. - p_WB1 << 0.1, 0.2, 0.3; - p_WB2 = p_WB1 + Eigen::Vector3d(1.0 / 3, 2.0 / 3, 2.0 / 3) * - (radius1_ + radius2_ + - 0.5 * constraint.minimum_distance_lower()); - - CheckConstraintEvalSmallerThanMinimumLowerDistance(constraint, p_WB1, - p_WB2); - } -#pragma GCC diagnostic pop - void CheckConstraintEval( const MinimumDistanceLowerBoundConstraint& constraint) const { // Distance between the spheres is larger than influence_distance @@ -380,211 +228,6 @@ class TwoFreeSpheresMinimumDistanceTest : public TwoFreeSpheresTest { } }; -#pragma GCC diagnostic push -#pragma GCC diagnostic ignored "-Wdeprecated-declarations" -TEST_F(TwoFreeSpheresMinimumDistanceTest, ExponentialPenalty) { - const double minimum_distance_lower{0.1}; - const double minimum_distance_upper{0.2}; - const double influence_distance{1.0}; - const MinimumDistanceConstraint constraint( - plant_double_, minimum_distance_lower, minimum_distance_upper, - plant_context_double_, solvers::ExponentiallySmoothedHingeLoss, - influence_distance); - CheckConstraintBounds(constraint); - - CheckConstraintEval(constraint); -} -#pragma GCC diagnostic pop - -#pragma GCC diagnostic push -#pragma GCC diagnostic ignored "-Wdeprecated-declarations" -TEST_F(TwoFreeSpheresMinimumDistanceTest, QuadraticallySmoothedHingePenalty) { - const double minimum_distance_lower{0.1}; - const double minimum_distance_upper{0.2}; - const double influence_distance{1.0}; - // The default penalty type is smoothed hinge. - const MinimumDistanceConstraint constraint( - plant_double_, minimum_distance_lower, minimum_distance_upper, - plant_context_double_, solvers::QuadraticallySmoothedHingeLoss, - influence_distance); - - CheckConstraintBounds(constraint); - - CheckConstraintEval(constraint); -} -#pragma GCC diagnostic pop - -#pragma GCC diagnostic push -#pragma GCC diagnostic ignored "-Wdeprecated-declarations" -GTEST_TEST(MinimumDistanceConstraintTest, - MultibodyPlantWithouthGeometrySource) { - auto plant = ConstructTwoFreeBodiesPlant(); - auto context = plant->CreateDefaultContext(); - DRAKE_EXPECT_THROWS_MESSAGE( - MinimumDistanceConstraint(plant.get(), 0.1, context.get()), - "Kinematic constraint: MultibodyPlant has not registered " - "with a SceneGraph yet. Please refer to " - "AddMultibodyPlantSceneGraph on how to connect MultibodyPlant to " - "SceneGraph."); -} -#pragma GCC diagnostic pop - -#pragma GCC diagnostic push -#pragma GCC diagnostic ignored "-Wdeprecated-declarations" -GTEST_TEST(MinimumDistanceConstraintTest, MultibodyPlantWithoutCollisionPairs) { - // Make sure MinimumDistanceConstraint evaluation works when - // no collisions are possible in an MBP with no collision geometry. - - systems::DiagramBuilder builder{}; - MultibodyPlant& plant = AddMultibodyPlantSceneGraph(&builder, 0.0); - AddTwoFreeBodiesToPlant(&plant); - plant.Finalize(); - auto diagram = builder.Build(); - auto diagram_context = diagram->CreateDefaultContext(); - auto plant_context = - &diagram->GetMutableSubsystemContext(plant, diagram_context.get()); - - const double minimum_distance(0.1); - const MinimumDistanceConstraint constraint(&plant, minimum_distance, - plant_context); - - Eigen::Matrix q_autodiff = - math::InitializeAutoDiff( - Eigen::VectorXd::Zero(kNumPositionsForTwoFreeBodies)); - AutoDiffVecXd y_autodiff(1); - constraint.Eval(q_autodiff, &y_autodiff); -} -#pragma GCC diagnostic pop - -#pragma GCC diagnostic push -#pragma GCC diagnostic ignored "-Wdeprecated-declarations" -TEST_F(TwoFreeSpheresTest, NonpositiveInfluenceDistanceOffset) { - DRAKE_EXPECT_THROWS_MESSAGE( - MinimumDistanceConstraint(plant_double_, 0.1, plant_context_double_, {}, - -0.05), - "MinimumDistanceConstraint: influence_distance=0.05, must be larger than " - "minimum_distance_lower=0.1; equivalently, " - "influence_distance_offset=-0.05, but it " - "needs to be positive."); - // We've already tested the message contents for a *smaller* influence - // distance. We'll assume the message is the same for an equal distance and - // just confirm the throw. - EXPECT_THROW(MinimumDistanceConstraint(plant_double_, 0.1, - plant_context_double_, {}, 0.0), - std::exception); -} -#pragma GCC diagnostic pop - -#pragma GCC diagnostic push -#pragma GCC diagnostic ignored "-Wdeprecated-declarations" -TEST_F(TwoFreeSpheresTest, NonfiniteInfluenceDistanceOffset) { - DRAKE_EXPECT_THROWS_MESSAGE( - MinimumDistanceConstraint(plant_double_, 0.1, plant_context_double_, {}, - std::numeric_limits::infinity()), - "MinimumDistanceConstraint: influence_distance must be finite."); - DRAKE_EXPECT_THROWS_MESSAGE( - MinimumDistanceConstraint(plant_double_, 0.1, plant_context_double_, {}, - std::numeric_limits::quiet_NaN()), - "MinimumDistanceConstraint: influence_distance must be finite."); -} -#pragma GCC diagnostic pop - -template -T BoxSphereSignedDistance(const Eigen::Vector3d& box_size, double radius, - const VectorX& x) { - const math::RigidTransform X_WB( - math::RotationMatrix(Eigen::Quaternion(x(0), x(1), x(2), x(3))), - x.template segment<3>(4)); - const math::RigidTransform X_WS( - math::RotationMatrix(Eigen::Quaternion(x(7), x(8), x(9), x(10))), - x.template tail<3>()); - return BoxSphereSignedDistance(box_size, radius, X_WB, X_WS); -} - -#pragma GCC diagnostic push -#pragma GCC diagnostic ignored "-Wdeprecated-declarations" -TEST_F(BoxSphereTest, TestDeprecate) { - const double minimum_distance = 0.01; - for (MinimumDistancePenaltyFunction penalty_function : - {QuadraticallySmoothedHingeLoss, ExponentiallySmoothedHingeLoss}) { - MinimumDistanceConstraint constraint(plant_double_, minimum_distance, - plant_context_double_, - penalty_function); - - auto check_eval_autodiff = [&constraint](const Eigen::VectorXd& q_val, - const Eigen::MatrixXd& q_gradient, - double tol, - const Eigen::Vector3d& box_size, - double radius) { - AutoDiffVecXd x_autodiff = math::InitializeAutoDiff(q_val, q_gradient); - - CheckConstraintEvalNonsymbolic(constraint, x_autodiff, tol); - }; - - Eigen::VectorXd q(kNumPositionsForTwoFreeBodies); - // First check q with normalized quaternion. - q.head<4>() = Eigen::Vector4d(1, 0, 0, 0); - q.segment<3>(4) = Eigen::Vector3d(0, 0, -5); - q.segment<4>(7) = Eigen::Vector4d(0.1, 0.7, 0.8, 0.9).normalized(); - q.tail<3>() << 0, 0, 0; - check_eval_autodiff( - q, - Eigen::MatrixXd::Identity(kNumPositionsForTwoFreeBodies, - kNumPositionsForTwoFreeBodies), - 1E-13, box_size_, radius_); - - q.tail<3>() << 0, 0, 1.1; - check_eval_autodiff( - q, - Eigen::MatrixXd::Identity(kNumPositionsForTwoFreeBodies, - kNumPositionsForTwoFreeBodies), - 1E-13, box_size_, radius_); - - // box and sphere are separated, but the separation distance is smaller than - // minimum_distance. - q.tail<3>() << 0, 0, 1.005; - check_eval_autodiff( - q, - Eigen::MatrixXd::Identity(kNumPositionsForTwoFreeBodies, - kNumPositionsForTwoFreeBodies), - 1E-11, box_size_, radius_); - - q.tail<3>() << 0, 0, -1; - check_eval_autodiff( - q, - Eigen::MatrixXd::Identity(kNumPositionsForTwoFreeBodies, - kNumPositionsForTwoFreeBodies), - 1E-13, box_size_, radius_); - - // Test a q with unnormalized quaternion. - q.head<4>() << 0.1, 1.7, 0.5, 0.3; - q.segment<4>(7) << 1, 0.1, 0.3, 2; - check_eval_autodiff( - q, - Eigen::MatrixXd::Identity(kNumPositionsForTwoFreeBodies, - kNumPositionsForTwoFreeBodies), - 1E-12, box_size_, radius_); - - // Now check if constraint constructed from MBP gives the same result - // as that from MBP - const MinimumDistanceConstraint constraint_from_autodiff( - plant_autodiff_, minimum_distance, plant_context_autodiff_, - penalty_function); - // Set dq to arbitrary values. - Eigen::Matrix dq; - for (int i = 0; i < 14; ++i) { - dq(i, 0) = std::sin(i + 1); - dq(i, 1) = 2 * i - 1; - } - /* tolerance for checking numerical gradient vs analytical gradient. The - * numerical gradient is only accurate up to 5E-6 */ - const double gradient_tol = 5E-6; - TestKinematicConstraintEval(constraint, constraint_from_autodiff, q, dq, - gradient_tol); - } -} -#pragma GCC diagnostic pop - /** Constructs a diagram that contains N free-floating spheres. */ @@ -644,174 +287,6 @@ class NFreeSpheresModel { std::unique_ptr> diagram_context_; }; -#pragma GCC diagnostic push -#pragma GCC diagnostic ignored "-Wdeprecated-declarations" -GTEST_TEST(ThreeSpheresTest, SomeLargerThanInfluenceSomeSmallerThanMinimum) { - // Test the case with three spheres. Some pair of spheres have distance > - // d_influence, and some pairs have distance < d_min. - NFreeSpheresModel three_spheres(3); - const double d_min = 0.05; - const double d_influence = 0.06; - // Indices into the q vector for each sphere's position. - Eigen::Index kSpheres[] = {4, 11, 18}; - Eigen::VectorXd q = - three_spheres.plant().GetPositions(three_spheres.plant_context()); - // Position for sphere 0. - q.segment<3>(kSpheres[0]) << 0, 0, 0; - // Position for sphere 1. - q.segment<3>(kSpheres[1]) << 0, 0, 0.05; - // Position for sphere 2. - q.segment<3>(kSpheres[2]) << 0, 0, 0.1; - // Make sure that distance(sphere0, sphere1) < d_min. - ASSERT_LT((q.segment<3>(kSpheres[0]) - q.segment<3>(kSpheres[1])).norm() - - 2 * three_spheres.radius(), - d_min); - // Make sure distance(sphere0, sphere2) > d_influence. - ASSERT_GT((q.segment<3>(kSpheres[2]) - q.segment<3>(kSpheres[0])).norm() - - 2 * three_spheres.radius(), - d_influence); - for (solvers::MinimumValuePenaltyFunction penalty_function : - {QuadraticallySmoothedHingeLoss, ExponentiallySmoothedHingeLoss}) { - MinimumDistanceConstraint dut(&(three_spheres.plant()), d_min, - &(three_spheres.get_mutable_plant_context()), - penalty_function, d_influence - d_min); - Eigen::VectorXd y_val; - dut.Eval(q, &y_val); - EXPECT_TRUE((y_val.array() < dut.lower_bound().array()).any() || - (y_val.array() > dut.upper_bound().array()).any()); - } -} -#pragma GCC diagnostic pop - -#pragma GCC diagnostic push -#pragma GCC diagnostic ignored "-Wdeprecated-declarations" -TEST_F(SpheresAndWallsTest, TestWithCollisionChecker) { - // Test MinimumDistanceConstraint constructed with CollisionChecker. - planning::CollisionCheckerParams params; - params.model = builder_.Build(); - params.robot_model_instances.push_back(multibody::default_model_instance()); - auto quaternion_difference = [](const Eigen::Ref& q1, - const Eigen::Ref& q2) { - // Compute 1-cos(theta/2) where theta is the angle between the two - // quaternions. - return 1 - (Eigen::Quaterniond(q1(0), q1(1), q1(2), q1(3)).conjugate() * - Eigen::Quaterniond(q2(0), q2(1), q2(2), q2(3))) - .w(); - }; - params.configuration_distance_function = [quaternion_difference]( - const Eigen::VectorXd& q1, - const Eigen::VectorXd& q2) { - return quaternion_difference(q1.head<4>(), q2.head<4>()) + - quaternion_difference(q1.segment<4>(7), q2.segment<4>(7)) + - (q1.segment<3>(4) - q2.segment<3>(4)).norm() + - (q1.segment<3>(11) - q2.segment<3>(11)).norm(); - }; - params.edge_step_size = 0.05; - planning::SceneGraphCollisionChecker collision_checker(std::move(params)); - auto collision_checker_context = - collision_checker.MakeStandaloneModelContext(); - double influence_distance = 0.2; - auto check_constraint = [&collision_checker]( - const MinimumDistanceConstraint& dut, - const Eigen::Vector3d& p_WS1, - const Eigen::Vector3d& p_WS2, bool is_satisfied) { - Eigen::VectorXd q(collision_checker.plant().num_positions()); - // sphere 1 quaternion. - q.head<4>() << 1, 0, 0, 0; - q.segment<3>(4) = p_WS1; - // sphere 2 quaternion. - q.segment<4>(7) << 1, 0, 0, 0; - q.tail<3>() = p_WS2; - EXPECT_EQ(dut.CheckSatisfied(q), is_satisfied); - // Make sure the gradient is correct. - const AutoDiffVecXd q_ad = math::InitializeAutoDiff(q); - AutoDiffVecXd y_ad; - dut.Eval(q_ad, &y_ad); - - math::NumericalGradientOption options( - math::NumericalGradientMethod::kCentral); - const Eigen::MatrixXd grad_numeric = - math::ComputeNumericalGradient( - [&dut](const Eigen::VectorXd& x, Eigen::VectorXd* y) { - dut.Eval(x, y); - }, - q, options); - EXPECT_TRUE( - CompareMatrices(math::ExtractGradient(y_ad), grad_numeric, 1E-7)); - }; - - { - // We provide both minimum_distance_lower and minimum_distance_upper. - double minimum_distance_lower = 0.05; - double minimum_distance_upper = 0.15; - MinimumDistanceConstraint dut( - &collision_checker, minimum_distance_lower, minimum_distance_upper, - collision_checker_context.get(), - solvers::QuadraticallySmoothedHingeLoss, influence_distance); - EXPECT_EQ(dut.num_constraints(), 2); - EXPECT_EQ(dut.num_vars(), collision_checker.plant().num_positions()); - - // The two spheres almost coincide (do not set the two spheres to exactly - // coincide as the distance jacobian is ill defined at that point). - check_constraint(dut, Eigen::Vector3d(0, 0, 0), Eigen::Vector3d(1E-4, 0, 0), - false); - // The two spheres are separated, but the distance is smaller than - // minimum_distance_lower - check_constraint( - dut, Eigen::Vector3d(0, 0, 0), - Eigen::Vector3d(0.9 * minimum_distance_lower + 2 * radius_, 0, 0), - false); - // The distance between the two spheres is between minimum_distance_lower - // and minimum_distance_upper. - check_constraint( - dut, Eigen::Vector3d(0, 0, 0), - Eigen::Vector3d( - (minimum_distance_lower + minimum_distance_upper) / 2 + 2 * radius_, - 0, 0), - true); - // The distance between the two spheres is above minimum_distance_upper. - check_constraint( - dut, Eigen::Vector3d(0, 0, 0), - Eigen::Vector3d(minimum_distance_upper + 2 * radius_ + 1E-3, 0, 0), - false); - // The distance between the two spheres is above minimum_distance_upper, but - // the distance between sphere 2 and the right wall is between - // minimum_distance_lower and minimum_distance_upper. - check_constraint( - dut, Eigen::Vector3d(0, 0, 0), - Eigen::Vector3d( - wall_length_ / 2 - - (minimum_distance_lower + minimum_distance_upper) / 2 - radius_, - 0, 0), - true); - } - - { - // Only specify minimum_distance_lower. - double minimum_distance = 0.05; - MinimumDistanceConstraint dut(&collision_checker, minimum_distance, - collision_checker_context.get()); - EXPECT_EQ(dut.num_constraints(), 1); - EXPECT_EQ(dut.num_vars(), collision_checker.plant().num_positions()); - - // The two spheres almost coincide (do not set the two spheres to exactly - // coincide as the distance jacobian is ill defined at that point). - check_constraint(dut, Eigen::Vector3d(0, 0, 0), Eigen::Vector3d(1E-4, 0, 0), - false); - // The two spheres are separated, but the distance is smaller than - // minimum_distance_lower. - check_constraint( - dut, Eigen::Vector3d(0, 0, 0), - Eigen::Vector3d(0.9 * minimum_distance + 2 * radius_, 0, 0), false); - // The distance between the two spheres is above minimum_distance. - check_constraint( - dut, Eigen::Vector3d(0, 0, 0), - Eigen::Vector3d(1.1 * minimum_distance + 2 * radius_, 0, 0), true); - } -} -#pragma GCC diagnostic pop - TEST_F(TwoFreeSpheresMinimumDistanceTest, ExponentialPenaltyLowerBound) { const double minimum_distance_lower{0.1}; const double influence_distance_offset{1.0}; diff --git a/multibody/plant/multibody_plant.h b/multibody/plant/multibody_plant.h index 99231af2f962..32fa724b9edb 100644 --- a/multibody/plant/multibody_plant.h +++ b/multibody/plant/multibody_plant.h @@ -2519,26 +2519,6 @@ class MultibodyPlant : public internal::MultibodyTreeSystem { internal_tree().GetPositionsAndVelocities(context, model_instance, qv_out); } - /// (Advanced -- **see warning**) Returns a mutable vector reference `[q; v]` - /// to the generalized positions q and generalized velocities v in a given - /// Context. - /// @warning Cache invalidation will occur when this is called but not if you - /// subsequently write through the returned object. You should use - /// SetPositionsAndVelocities() instead unless you are - /// fully aware of the interactions with the caching mechanism (see - /// @ref dangerous_get_mutable). - /// @throws std::exception if `context` is nullptr or if it does not - /// correspond to the context for a multibody model. - DRAKE_DEPRECATED( - "2024-02-01", - "Use GetPositionsAndVelocities() for constant access and " - "SetPositionsAndVelocities() to set the positions and velocities.") - Eigen::VectorBlock> GetMutablePositionsAndVelocities( - systems::Context* context) const { - this->ValidateContext(context); - return internal_tree().GetMutablePositionsAndVelocities(context); - } - /// Sets generalized positions q and generalized velocities v in a given /// Context from a given vector [q; v]. Prefer this method over /// GetMutablePositionsAndVelocities(). @@ -2609,42 +2589,6 @@ class MultibodyPlant : public internal::MultibodyTreeSystem { model_instance, internal_tree().get_positions(context), q_out); } - /// (Advanced -- **see warning**) Returns a mutable vector reference to the - /// generalized positions q in a given Context. - /// @warning Cache invalidation will occur when this is called but not - /// if you subsequently write through the returned object. You - /// should use SetPositions() instead unless you are fully aware - /// of the possible interactions with the caching mechanism (see - /// @ref dangerous_get_mutable). - /// @throws std::exception if the `context` is nullptr or if it does not - /// correspond to the Context for a multibody model. - DRAKE_DEPRECATED("2024-02-01", - "Use GetPositions() for constant access and SetPositions() " - "to set positions.") - Eigen::VectorBlock> GetMutablePositions( - systems::Context* context) const { - this->ValidateContext(context); - return internal_tree().GetMutablePositions(context); - } - - /// (Advanced) Returns a mutable vector reference to the generalized positions - /// q in a given State. - /// @note This method returns a reference to existing data, exhibits constant - /// i.e., O(1) time complexity, and runs very quickly. No cache - /// invalidation occurs. - /// @throws std::exception if the `state` is nullptr or if `context` does - /// not correspond to the Context for a multibody model. - /// @pre `state` comes from this multibody model. - DRAKE_DEPRECATED("2024-02-01", - "Use GetPositions() for constant access and SetPositions() " - "to set positions.") - Eigen::VectorBlock> GetMutablePositions( - const systems::Context& context, systems::State* state) const { - this->ValidateContext(context); - this->ValidateCreatedForThisSystem(state); - return internal_tree().get_mutable_positions(state); - } - /// Sets the generalized positions q in a given Context from a given vector. /// Prefer this method over GetMutablePositions(). /// @throws std::exception if `context` is nullptr, if `context` does not @@ -2762,42 +2706,6 @@ class MultibodyPlant : public internal::MultibodyTreeSystem { model_instance, internal_tree().get_velocities(context), v_out); } - /// (Advanced -- **see warning**) Returns a mutable vector reference to the - /// generalized velocities v in a given Context. - /// @warning Cache invalidation will occur when this is called but not - /// if you subsequently write through the returned object. You - /// should use SetVelocities() instead unless you are fully aware - /// of the possible interactions with the caching mechanism (see - /// @ref dangerous_get_mutable). - /// @throws std::exception if the `context` is nullptr or if it does not - /// correspond to the Context for a multibody model. - DRAKE_DEPRECATED("2024-02-01", - "Use GetVelocities() for constant access and " - "SetVelocities() to set velocities.") - Eigen::VectorBlock> GetMutableVelocities( - systems::Context* context) const { - this->ValidateContext(context); - return internal_tree().GetMutableVelocities(context); - } - - /// (Advanced) Returns a mutable vector reference to the generalized - /// velocities v in a given State. - /// @note This method returns a reference to existing data, exhibits constant - /// i.e., O(1) time complexity, and runs very quickly. No cache - /// invalidation occurs. - /// @throws std::exception if the `state` is nullptr or if `context` does - /// not correspond to the Context for a multibody model. - /// @pre `state` comes from this multibody model. - DRAKE_DEPRECATED("2024-02-01", - "Use GetVelocities() for constant access and " - "SetVelocities() to set velocities.") - Eigen::VectorBlock> GetMutableVelocities( - const systems::Context& context, systems::State* state) const { - this->ValidateContext(context); - this->ValidateCreatedForThisSystem(state); - return internal_tree().get_mutable_velocities(state); - } - /// Sets the generalized velocities v in a given Context from a given /// vector. Prefer this method over GetMutableVelocities(). /// @throws std::exception if the `context` is nullptr, if the context does diff --git a/multibody/plant/test/calc_distance_and_time_derivative_test.cc b/multibody/plant/test/calc_distance_and_time_derivative_test.cc index f7a47305d8ac..254dc49f39c0 100644 --- a/multibody/plant/test/calc_distance_and_time_derivative_test.cc +++ b/multibody/plant/test/calc_distance_and_time_derivative_test.cc @@ -31,13 +31,6 @@ void CheckDistanceAndTimeDerivative( v.segment<3>(sphere_body.floating_velocities_start_in_v()) = omega_WS; v.segment<3>(sphere_body.floating_velocities_start_in_v() + 3) = v_WS; - // TODO(sherm1) Remove as of 2024-02-01 -#pragma GCC diagnostic push -#pragma GCC diagnostic ignored "-Wdeprecated-declarations" - EXPECT_EQ(box_body.floating_velocities_start(), - 14 + box_body.floating_velocities_start_in_v()); -#pragma GCC diagnostic push - plant.SetPositions(plant_context, q); plant.SetVelocities(plant_context, v); const SignedDistanceWithTimeDerivative result = diff --git a/multibody/plant/test/multibody_plant_test.cc b/multibody/plant/test/multibody_plant_test.cc index f561fa2e5a06..f1dea4dcc93f 100644 --- a/multibody/plant/test/multibody_plant_test.cc +++ b/multibody/plant/test/multibody_plant_test.cc @@ -2854,20 +2854,6 @@ TEST_P(KukaArmTest, StateAccess) { // Modify positions and change xc expected to reflect changes to positions. for (int i = 0; i < plant_->num_positions(); ++i) xc_expected[i] *= -1; -#pragma GCC diagnostic push -#pragma GCC diagnostic ignored "-Wdeprecated-declarations" - plant_->GetMutablePositions(context_.get()) = - xc_expected.head(plant_->num_positions()); -#pragma GCC diagnostic pop - EXPECT_EQ(plant_->GetPositions(*context_), - xc_expected.head(plant_->num_positions())); - EXPECT_EQ(xc, xc_expected); - - // SetPositions() should yield the same result. -#pragma GCC diagnostic push -#pragma GCC diagnostic ignored "-Wdeprecated-declarations" - plant_->GetMutablePositions(context_.get()).setZero(); -#pragma GCC diagnostic pop plant_->SetPositions(context_.get(), xc_expected.head(plant_->num_positions())); EXPECT_EQ(plant_->GetPositions(*context_), @@ -2876,37 +2862,12 @@ TEST_P(KukaArmTest, StateAccess) { // Modify velocities and change xc_expected to reflect changes to velocities. for (int i = 0; i < plant_->num_velocities(); ++i) xc_expected[i + plant_->num_positions()] *= -1; -#pragma GCC diagnostic push -#pragma GCC diagnostic ignored "-Wdeprecated-declarations" - plant_->GetMutableVelocities(context_.get()) = - xc_expected.tail(plant_->num_velocities()); -#pragma GCC diagnostic pop - EXPECT_EQ(plant_->GetVelocities(*context_), - xc_expected.tail(plant_->num_velocities())); - EXPECT_EQ(xc, xc_expected); - - // SetVelocities() should yield the same result. -#pragma GCC diagnostic push -#pragma GCC diagnostic ignored "-Wdeprecated-declarations" - plant_->GetMutableVelocities(context_.get()).setZero(); -#pragma GCC diagnostic pop plant_->SetVelocities(context_.get(), xc_expected.tail(plant_->num_velocities())); EXPECT_EQ(plant_->GetVelocities(*context_), xc_expected.tail(plant_->num_velocities())); EXPECT_EQ(xc, xc_expected); - // Get a mutable state and modify it. - // Note: xc above is referencing values stored in the context. Therefore - // setting the entire state to zero changes the values referenced by xc. -#pragma GCC diagnostic push -#pragma GCC diagnostic ignored "-Wdeprecated-declarations" - plant_->GetMutablePositionsAndVelocities(context_.get()).setZero(); -#pragma GCC diagnostic pop - EXPECT_EQ(xc, VectorX::Zero(plant_->num_multibody_states())); - plant_->SetPositionsAndVelocities(context_.get(), xc_expected); - EXPECT_EQ(xc, xc_expected); - // Ensure that call sites accepting a VectorBlock do not allocate. auto q_block = xc_expected.head(plant_->num_positions()); auto v_block = xc_expected.tail(plant_->num_velocities()); @@ -4699,11 +4660,6 @@ GTEST_TEST(MultibodyPlantTest, FloatingJointNames) { SpatialInertia::MakeUnitary()); plant.Finalize(); EXPECT_NO_THROW(plant.GetJointByName("free_body")); - - // Deprecated; remove after 2024-02-01. - // Previously floating joint names were prefixed with $world_. - // GetJointByName() removes that and logs a deprecation warning. - EXPECT_NO_THROW(plant.GetJointByName("$world_free_body")); } // Verify that in case of a name conflict, we prepend with underscores @@ -4728,13 +4684,6 @@ GTEST_TEST(MultibodyPlantTest, FloatingJointNames) { plant.Finalize(); EXPECT_NO_THROW(plant.GetJointByName("__base_body")); - - // We do not have deprecation support for this case. Previously the - // added joint would have been named "$world_base_body". During the - // deprecation period, GetJointByName("$world_base_body") will strip - // "$world_" and incorrectly return the unrelated joint unfortunately named - // "base_body". However a warning will be logged noting that. (remove - // comment 2024-02-01) } } diff --git a/multibody/tree/fixed_offset_frame.h b/multibody/tree/fixed_offset_frame.h index e90adc474210..a971298301de 100644 --- a/multibody/tree/fixed_offset_frame.h +++ b/multibody/tree/fixed_offset_frame.h @@ -5,7 +5,6 @@ #include #include "drake/common/default_scalars.h" -#include "drake/common/drake_deprecated.h" #include "drake/common/eigen_types.h" #include "drake/multibody/tree/frame.h" #include "drake/multibody/tree/multibody_tree_topology.h" diff --git a/multibody/tree/frame.h b/multibody/tree/frame.h index 4c4da741082c..4f0f15878414 100644 --- a/multibody/tree/frame.h +++ b/multibody/tree/frame.h @@ -5,7 +5,6 @@ #include #include "drake/common/autodiff.h" -#include "drake/common/drake_deprecated.h" #include "drake/common/nice_type_name.h" #include "drake/multibody/math/spatial_algebra.h" #include "drake/multibody/tree/frame_base.h" diff --git a/multibody/tree/mobilizer.h b/multibody/tree/mobilizer.h index 77d491bbfd31..226710f4e41a 100644 --- a/multibody/tree/mobilizer.h +++ b/multibody/tree/mobilizer.h @@ -7,7 +7,6 @@ #include "drake/common/autodiff.h" #include "drake/common/drake_assert.h" #include "drake/common/drake_copyable.h" -#include "drake/common/drake_deprecated.h" #include "drake/common/random.h" #include "drake/multibody/math/spatial_algebra.h" #include "drake/multibody/tree/frame.h" diff --git a/multibody/tree/multibody_tree-inl.h b/multibody/tree/multibody_tree-inl.h index cf3d803e2b8c..63aaa12f60ba 100644 --- a/multibody/tree/multibody_tree-inl.h +++ b/multibody/tree/multibody_tree-inl.h @@ -13,7 +13,6 @@ #include "drake/common/default_scalars.h" #include "drake/common/drake_copyable.h" -#include "drake/common/drake_deprecated.h" #include "drake/common/pointer_cast.h" #include "drake/common/random.h" #include "drake/multibody/tree/acceleration_kinematics_cache.h" diff --git a/multibody/tree/multibody_tree.h b/multibody/tree/multibody_tree.h index 8a9bf2a58d56..ba5c8e768d53 100644 --- a/multibody/tree/multibody_tree.h +++ b/multibody/tree/multibody_tree.h @@ -17,7 +17,6 @@ #include "drake/common/default_scalars.h" #include "drake/common/drake_copyable.h" -#include "drake/common/drake_deprecated.h" #include "drake/common/pointer_cast.h" #include "drake/common/random.h" #include "drake/math/rigid_transform.h" @@ -791,20 +790,6 @@ class MultibodyTree { std::optional model_instance = std::nullopt) const { static_assert(std::is_base_of_v, JointType>, "JointType must be a sub-class of Joint."); - - // Backwards compatibility for automatically-added floating joints whose - // names went from "$world_bodyname" to "bodyname". Does not attempt to - // support cases (rare, maybe nonexistent) where a conflict caused the new - // name to be prefixed by underscores. Remove this on or after 2024-02-01. - if (name.substr(0, 7) == "$world_") { - name.remove_prefix(7); - drake::log()->warn( - "GetJointByName($world_{}): Floating joint names are no longer " - "prefixed by '$world_'. Looking for joint {} instead. " - "Support for the '$world_' prefix is deprecated and will " - "be removed on or after 2024-02-01.", name, name); - } - const Joint& joint = GetJointByNameImpl(name, model_instance); const JointType* const typed_joint = dynamic_cast*>(&joint); @@ -1163,44 +1148,6 @@ class MultibodyTree { // @name Methods to compute multibody Jacobians. // @{ - // See MultibodyPlant method. - VectorX CalcBiasForJacobianTranslationalVelocity( - const systems::Context& context, - JacobianWrtVariable with_respect_to, - const Frame& frame_F, - const Eigen::Ref>& p_FP_list, - const Frame& frame_A, - const Frame& frame_E) const { - const int num_points = p_FP_list.cols(); - DRAKE_THROW_UNLESS(num_points > 0 && p_FP_list.rows() == 3); - - const Matrix3X asBias_AFp_E = CalcBiasTranslationalAcceleration( - context, with_respect_to, frame_F, p_FP_list, frame_A, frame_E); - - // This deprecated method needs to return a VectorX. - VectorX asBias_AFp_E_as_VectorX(3 * num_points); - for (int i = 0; i < num_points; ++i) { - const Vector3 acceleration_bias_i = asBias_AFp_E.col(i); - for (int j = 0; j < 3; ++j) - asBias_AFp_E_as_VectorX(3*i + j) = acceleration_bias_i(j); - } - - return asBias_AFp_E_as_VectorX; - } - - // See MultibodyPlant method. - Vector6 CalcBiasForJacobianSpatialVelocity( - const systems::Context& context, - JacobianWrtVariable with_respect_to, - const Frame& frame_F, - const Eigen::Ref>& p_FoFp_F, - const Frame& frame_A, - const Frame& frame_E) const { - const SpatialAcceleration Abias_WFp = CalcBiasSpatialAcceleration( - context, with_respect_to, frame_F, p_FoFp_F, frame_A, frame_E); - return Abias_WFp.get_coeffs(); - } - // See MultibodyPlant method. void CalcJacobianSpatialVelocity( const systems::Context& context, diff --git a/multibody/tree/rigid_body.h b/multibody/tree/rigid_body.h index 0f015d27a731..0524372fb290 100644 --- a/multibody/tree/rigid_body.h +++ b/multibody/tree/rigid_body.h @@ -326,25 +326,6 @@ class RigidBody : public MultibodyElement { return topology_.floating_positions_start; } - /// (Advanced, Deprecated) For floating bodies (see is_floating()) this - /// method returns the index of this %RigidBody's first generalized velocity - /// in the _full state vector_ for a MultibodyPlant model, under the dubious - /// assumption that the state consists of [q v] concatenated. - /// Velocities for this body are then contiguous starting at this index. - /// @throws std::exception if called pre-finalize - /// @pre this is a floating body - /// @see floating_velocities_start_in_v() - DRAKE_DEPRECATED("2024-02-01", - "Convert to floating_velocities_start_in_v(). In a state " - "with [q v] concatenated, offset by num_positions() to " - "get to the start of v.") - int floating_velocities_start() const { - ThrowIfNotFinalized(__func__); - DRAKE_DEMAND(is_floating()); - return this->get_parent_tree().num_positions() + - topology_.floating_velocities_start_in_v; - } - /// (Advanced) For floating bodies (see is_floating()) this method returns the /// index of this %RigidBody's first generalized velocity in the vector v of /// generalized velocities for a MultibodyPlant model. Velocities v for this diff --git a/multibody/tree/test/multibody_tree_test.cc b/multibody/tree/test/multibody_tree_test.cc index d64a83d5a218..dc2a60396bdc 100644 --- a/multibody/tree/test/multibody_tree_test.cc +++ b/multibody/tree/test/multibody_tree_test.cc @@ -941,129 +941,6 @@ TEST_F(KukaIiwaModelTests, CalcJacobianTranslationalVelocityB) { MatrixCompareType::relative)); } - -// Unit tests MBT::CalcBiasForJacobianTranslationalVelocity() using -// AutoDiffXd to compute time derivatives of a Jacobian to obtain a -// reference solution. -#pragma GCC diagnostic push -#pragma GCC diagnostic ignored "-Wdeprecated-declarations" -TEST_F(KukaIiwaModelTests, CalcBiasForJacobianTranslationalVelocity) { - // The number of generalized positions in the Kuka iiwa robot arm model. - const int kNumPositions = tree().num_positions(); - - // Numerical tolerance used to verify numerical results. - const double kTolerance = 10 * std::numeric_limits::epsilon(); - - // Get a set of joint angles and angular rates that avoids in-plane motion. - VectorX q, v; - GetArbitraryNonZeroJointAnglesAndRates(&q, &v); - - // Since the bias term is a function of q and v only (i.e. it is not a - // function of vdot), we choose a set of arbitrary values for the generalized - // accelerations. We do purposely set this values to be non-zero to stress - // the fact that the bias term is not a function of vdot. - VectorX vdot(kNumPositions); - vdot << 1, 2, 3, 4, 5, 6, 7; - - // Set generalized positions and velocities. - int angle_index = 0; - for (const RevoluteJoint* joint : joints_) { - joint->set_angle(context_.get(), q[angle_index]); - joint->set_angular_rate(context_.get(), v[angle_index]); - angle_index++; - } - - context_autodiff_->SetTimeStateAndParametersFrom(*context_); - - // Initialize q_autodiff and v_autodiff so that we differentiate with respect - // to time. - // Note: here we pass MatrixXd(v) so that the return gradient uses AutoDiffXd - // (for which we do have explicit instantiations) instead of - // AutoDiffScalar. - auto q_autodiff = math::InitializeAutoDiff(q, MatrixXd(v)); - auto v_autodiff = math::InitializeAutoDiff(v, MatrixXd(vdot)); - - VectorX x_autodiff(2 * kNumPositions); - x_autodiff << q_autodiff, v_autodiff; - - // Set the context for AutoDiffXd computations. - tree_autodiff().GetMutablePositionsAndVelocities(context_autodiff_.get()) - = x_autodiff; - - // A set of points Pi attached to frame H on the end effector. - const int kNumPoints = 2; // The set stores 2 points. - MatrixX p_HPi(3, kNumPoints); - p_HPi.col(0) << 0.1, -0.05, 0.02; - p_HPi.col(1) << 0.2, 0.3, -0.15; - - MatrixX p_WPi(3, kNumPoints); - MatrixX Jv_WHp(3 * kNumPoints, kNumPositions); - - const MatrixX p_HPi_autodiff = p_HPi; - MatrixX p_WPi_autodiff(3, kNumPoints); - MatrixX Jv_WHp_autodiff(3 * kNumPoints, kNumPositions); - - // Compute J̇v_v_WHp using AutoDiffXd. - CalcPointsOnFrameHTranslationalVelocityJacobianWrtV( - tree_autodiff(), *context_autodiff_, p_HPi_autodiff, - &p_WPi_autodiff, &Jv_WHp_autodiff); - - // Extract time derivatives: - MatrixX Jv_WHp_derivs = math::ExtractGradient(Jv_WHp_autodiff); - Jv_WHp_derivs.resize(3 * kNumPoints, kNumPositions); - - // Compute the expected value of the bias terms using the time derivatives - // computed with AutoDiffXd. - const VectorX abias_WHp_W_expected = Jv_WHp_derivs * v; - - // Compute bias for Jacobian translational velocity. - const Frame& world_frame = tree().world_frame(); - const VectorX abias_WHp_W = - tree().CalcBiasForJacobianTranslationalVelocity( - *context_, JacobianWrtVariable::kV, *frame_H_, p_HPi, - world_frame, world_frame); - - // abias_WHp is of size 3⋅kNumPoints x num_velocities. CompareMatrices() below - // verifies this, in addition to the numerical values of each element. - EXPECT_TRUE(CompareMatrices(abias_WHp_W, abias_WHp_W_expected, - kTolerance, MatrixCompareType::relative)); - - // Express the expected bias acceleration result in frame_H_. - const RotationMatrix R_WH = - frame_H_->CalcRotationMatrixInWorld(*context_); - const RotationMatrix R_HW = R_WH.inverse(); - Vector6 abias_WHp_H_expected; - abias_WHp_H_expected.head(3) = R_HW * abias_WHp_W_expected.head(3); - abias_WHp_H_expected.tail(3) = R_HW * abias_WHp_W_expected.tail(3); - - // Directly calculate abias_WHp_H. - const VectorX abias_WHp_H = - tree().CalcBiasForJacobianTranslationalVelocity( - *context_, JacobianWrtVariable::kV, *frame_H_, p_HPi, - world_frame, *frame_H_); - - // Ensure abias_WHp_H is nearly identical to abias_WHp_H_expected. - EXPECT_TRUE(CompareMatrices(abias_WHp_H, abias_WHp_H_expected, - kTolerance, MatrixCompareType::relative)); - - // Verify CalcBiasForJacobianTranslationalVelocity() throws an exception if - // the input set of points is not represented as a matrix with three rows. - MatrixX p_HQi(5, kNumPoints); // an invalid size input set. - DRAKE_EXPECT_THROWS_MESSAGE( - tree().CalcBiasForJacobianTranslationalVelocity( - *context_, JacobianWrtVariable::kV, *frame_H_, p_HQi, - world_frame, world_frame), - ".* condition '.*.rows\\(\\) == 3' failed."); - - // Verify CalcBiasForJacobianTranslationalVelocity() throws an exception if - // JacobianWrtVariable is KQDot (not kV). - EXPECT_THROW(tree().CalcBiasForJacobianTranslationalVelocity( - *context_, JacobianWrtVariable::kQDot, *frame_H_, p_HPi, - world_frame, world_frame), - std::exception); -} -#pragma GCC diagnostic pop // pop -Wdeprecated-declarations - // Given a set of points Pi attached to the end effector frame G, this test // calculates Jq̇_v_WPi (Pi's translational velocity Jacobian with respect to q̇) // using two methods: @@ -1246,92 +1123,6 @@ TEST_F(KukaIiwaModelTests, CalcJacobianSpatialVelocityA) { EXPECT_TRUE(Jv_WF_times_v.IsApprox(V_WEf, kTolerance)); } - -// Unit tests MBT::CalcBiasForJacobianSpatialVelocity() use AutoDiffXd to time- -// differentiate a spatial velocity Jacobian to form a reference solution. -#pragma GCC diagnostic push -#pragma GCC diagnostic ignored "-Wdeprecated-declarations" -TEST_F(KukaIiwaModelTests, CalcBiasForJacobianSpatialVelocity) { - // The number of generalized velocities in the Kuka iiwa robot arm model. - const int kNumVelocities = tree().num_velocities(); - - // Numerical tolerance used to verify numerical results. - const double kTolerance = 10 * std::numeric_limits::epsilon(); - - // Get a set of joint angles and angular rates that avoids in-plane motion. - VectorX q, v; - GetArbitraryNonZeroJointAnglesAndRates(&q, &v); - - // Since the bias term is a function of q and v only (i.e. it is not a - // function of vdot), we choose a set of arbitrary values for the generalized - // accelerations. We do purposely set this values to be non-zero to stress - // the fact that the bias term is not a function of vdot. - const VectorX vdot = - VectorX::Constant( - kNumVelocities, std::numeric_limits::quiet_NaN()); - - // Set generalized positions and velocities. - int angle_index = 0; - for (const RevoluteJoint* joint : joints_) { - joint->set_angle(context_.get(), q[angle_index]); - joint->set_angular_rate(context_.get(), v[angle_index]); - angle_index++; - } - - context_autodiff_->SetTimeStateAndParametersFrom(*context_); - - // Initialize q_autodiff and v_autodiff so that we differentiate with respect - // to time. - // Note: here we pass MatrixXd(v) so that the return gradient uses AutoDiffXd - // (for which we do have explicit instantiations) instead of - // AutoDiffScalar. - auto q_autodiff = math::InitializeAutoDiff(q, MatrixXd(v)); - auto v_autodiff = math::InitializeAutoDiff(v, MatrixXd(vdot)); - - VectorX x_autodiff(2 * kNumVelocities); - x_autodiff << q_autodiff, v_autodiff; - - // Set the context for AutoDiffXd computations. - tree_autodiff().GetMutablePositionsAndVelocities(context_autodiff_.get()) - = x_autodiff; - - // Po specifies the position of a new frame Hp which is the result of shifting - // frame H from Ho to Po. - Vector3 p_HPo(0.1, -0.05, 0.02); - - // Compute the spatial velocity Jacobian with respect to generalized - // velocities v for a frame H shifted to point Hp. - MatrixX Jv_WHp(6, kNumVelocities); - - const Vector3 p_HPo_autodiff = p_HPo; - MatrixX Jv_WHp_autodiff(6, kNumVelocities); - - // Compute J̇v_V_WHp using AutoDiffXd. - CalcFrameHpJacobianSpatialVelocityInWorld( - tree_autodiff(), *context_autodiff_, p_HPo_autodiff, &Jv_WHp_autodiff); - - // Extract time derivatives: - MatrixX Jv_WHp_derivs = math::ExtractGradient(Jv_WHp_autodiff); - Jv_WHp_derivs.resize(6, kNumVelocities); - - // Compute the expected value of the bias terms using the time derivatives - // computed with AutoDiffXd. - const VectorX Abias_WHp_expected = Jv_WHp_derivs * v; - - // Compute point Hp's spatial velocity Jacobian bias in world W. - const Frame& world_frame = tree().world_frame(); - const VectorX Abias_WHp = - tree().CalcBiasForJacobianSpatialVelocity( - *context_, JacobianWrtVariable::kV, *frame_H_, p_HPo, - world_frame, world_frame); - - // Abias_WHp is of size 6 x num_velocities. CompareMatrices() below - // verifies this, in addition to the numerical values of each element. - EXPECT_TRUE(CompareMatrices(Abias_WHp, Abias_WHp_expected, - kTolerance, MatrixCompareType::relative)); -} -#pragma GCC diagnostic pop // pop -Wdeprecated-declarations - // Verify that even when the input set of points and/or the Jacobian might // contain garbage on input, a query for the world body Jacobian will always // yield the following results: diff --git a/multibody/tree/weld_joint.h b/multibody/tree/weld_joint.h index 14ccd08e8036..446be7b11138 100644 --- a/multibody/tree/weld_joint.h +++ b/multibody/tree/weld_joint.h @@ -7,7 +7,6 @@ #include "drake/common/default_scalars.h" #include "drake/common/drake_copyable.h" -#include "drake/common/drake_deprecated.h" #include "drake/multibody/tree/joint.h" #include "drake/multibody/tree/multibody_forces.h" #include "drake/multibody/tree/weld_mobilizer.h" diff --git a/solvers/minimum_value_constraint.cc b/solvers/minimum_value_constraint.cc index 98996d81ce08..d10c7cc9c20e 100644 --- a/solvers/minimum_value_constraint.cc +++ b/solvers/minimum_value_constraint.cc @@ -205,181 +205,6 @@ void QuadraticallySmoothedHingeLoss(double x, double* penalty, } } -MinimumValueConstraint::MinimumValueConstraint( - int num_vars, double minimum_value, double influence_value_offset, - int max_num_values, - std::function&, double)> - value_function, - std::function(const Eigen::Ref>&, - double)> - value_function_double) - : MinimumValueConstraint(num_vars, minimum_value, kInf, - minimum_value + influence_value_offset, - max_num_values, std::move(value_function), - std::move(value_function_double)) {} - -namespace { -int NumConstraints(double minimum_value_lower, double minimum_value_upper) { - if (std::isfinite(minimum_value_lower) || - std::isfinite(minimum_value_upper)) { - return static_cast(std::isfinite(minimum_value_lower)) + - static_cast(std::isfinite(minimum_value_upper)); - } else { - throw std::runtime_error(fmt::format( - "MinimumValueConstraint: minimum_value_lower={}, " - "minimum_value_upper={}. At least one of them should be finite.", - minimum_value_lower, minimum_value_upper)); - } -} - -Eigen::VectorXd LowerBounds(double minimum_value_lower, - double minimum_value_upper) { - // We assume at least one of minimum_value_lower and minimum_value_upper is - // finite, as checked already in NumConstraints(). - if (std::isfinite(minimum_value_lower) && - std::isfinite(minimum_value_upper)) { - return Eigen::Vector2d(-kInf, 1); - } else if (std::isfinite(minimum_value_lower)) { - return Vector1d(-kInf); - } else if (std::isfinite(minimum_value_upper)) { - return Vector1d(1); - } - DRAKE_UNREACHABLE(); -} - -Eigen::VectorXd UpperBounds(double minimum_value_lower, - double minimum_value_upper) { - // We assume at least one of minimum_value_lower and minimum_value_upper is - // finite, as checked already in NumConstraints(). - if (std::isfinite(minimum_value_lower) && - std::isfinite(minimum_value_upper)) { - return Eigen::Vector2d(1, kInf); - } else if (std::isfinite(minimum_value_lower)) { - return Vector1d(1); - } else if (std::isfinite(minimum_value_upper)) { - return Vector1d(kInf); - } - DRAKE_UNREACHABLE(); -} -} // namespace - -MinimumValueConstraint::MinimumValueConstraint( - int num_vars, double minimum_value_lower, double minimum_value_upper, - double influence_value, int max_num_values, - std::function&, double)> - value_function, - std::function(const Eigen::Ref>&, - double)> - value_function_double) - : Constraint(NumConstraints(minimum_value_lower, minimum_value_upper), - num_vars, - LowerBounds(minimum_value_lower, minimum_value_upper), - UpperBounds(minimum_value_lower, minimum_value_upper)), - value_function_{std::move(value_function)}, - value_function_double_{std::move(value_function_double)}, - minimum_value_lower_{minimum_value_lower}, - minimum_value_upper_{minimum_value_upper}, - influence_value_{influence_value}, - max_num_values_{max_num_values} { - DRAKE_DEMAND(!std::isnan(minimum_value_lower_)); - DRAKE_DEMAND(!std::isnan(minimum_value_upper_)); - DRAKE_DEMAND(influence_value_ > minimum_value_lower_); - if (std::isfinite(minimum_value_upper)) { - DRAKE_DEMAND(influence_value_ > minimum_value_upper_); - } - DRAKE_DEMAND(std::isfinite(influence_value_)); - this->set_penalty_function(QuadraticallySmoothedHingeLoss); -} - -void MinimumValueConstraint::set_penalty_function( - MinimumValuePenaltyFunction new_penalty_function) { - set_penalty_function_impl(new_penalty_function, &penalty_function_, - &penalty_output_scaling_); -} - -template -void MinimumValueConstraint::EvalMaxPenalty( - double bound_value, const VectorX& values, int y_index, - const std::function&)>& smooth_func, - VectorX* y) const { - if (y_index >= 0) { - EvalPenalty(bound_value, values, max_num_values_, influence_value_, - penalty_function_, penalty_output_scaling_, smooth_func, - y->data() + y_index); - } -} - -template -void MinimumValueConstraint::DoEvalGeneric( - const Eigen::Ref>& x, VectorX* y) const { - y->resize(num_constraints()); - - // Indices for the one or two possible constraints. Infinite bound valuess map - // to invalid index values (-1). - // SoftOverMax(φ((vᵢ - v_influence)/(v_influence - vₘᵢₙ_lower)) / φ(-1)) ≤ 1. - const int y_lower_index = std::isfinite(minimum_value_lower_) ? 0 : -1; - // Index for the constraint - // SoftUnderMax( φ((vᵢ - v_influence)/(v_influence - vₘᵢₙ_upper)) / φ(-1) ) ≥ - // 1. - const int y_upper_index = - std::isfinite(minimum_value_upper_) ? y_lower_index + 1 : -1; - - // If we know that Values() will return at most zero values, then this - // is a non-constraint. Return zero for the lower bound constraint, and 2 for - // the upper bound constraint. - if (max_num_values_ == 0) { - if (y_lower_index >= 0) { - // The upper bound is 1. Set the value to 0 to guarantee that the - // constraint is satisfied. - InitializeY(x, y, y_lower_index, 0.0); - } - if (y_upper_index >= 0) { - // The lower bound is 1. Set the value to 2 to guarantee that the - // constraint is satisfied. - InitializeY(x, y, y_upper_index, 2.0); - } - return; - } - - // Initialize y(y_lower_index) and y(y_upper_index) to - // SmoothOverMax([0,..., 0]) and SmoothUnderMax([0, ..., 0]), respectively. - if (y_lower_index >= 0) { - InitializeY(x, y, y_lower_index, - SmoothOverMax(std::vector(max_num_values_, 0.0))); - } - if (y_upper_index >= 0) { - InitializeY(x, y, y_upper_index, - SmoothUnderMax(std::vector(max_num_values_, 0.0))); - } - - VectorX values = - Values(x, influence_value_, value_function_double_, value_function_); - const int num_values = static_cast(values.size()); - DRAKE_ASSERT(num_values <= max_num_values_); - this->EvalMaxPenalty( - minimum_value_lower_, values, y_lower_index, - [](const std::vector& v) { - return SmoothOverMax(v); - }, - y); - this->EvalMaxPenalty( - minimum_value_upper_, values, y_upper_index, - [](const std::vector& v) { - return SmoothUnderMax(v); - }, - y); -} - -void MinimumValueConstraint::DoEval(const Eigen::Ref& x, - Eigen::VectorXd* y) const { - DoEvalGeneric(x, y); -} - -void MinimumValueConstraint::DoEval(const Eigen::Ref& x, - AutoDiffVecXd* y) const { - DoEvalGeneric(x, y); -} - MinimumValueLowerBoundConstraint::MinimumValueLowerBoundConstraint( int num_vars, double minimum_value_lower, double influence_value_offset, int max_num_values, diff --git a/solvers/minimum_value_constraint.h b/solvers/minimum_value_constraint.h index dacd0afd6e7f..cc173ca6cef4 100644 --- a/solvers/minimum_value_constraint.h +++ b/solvers/minimum_value_constraint.h @@ -4,7 +4,6 @@ #include #include -#include "drake/common/drake_deprecated.h" #include "drake/solvers/constraint.h" namespace drake { @@ -50,167 +49,6 @@ multidisciplinary workshop on Advances in Preference Handling. */ void QuadraticallySmoothedHingeLoss(double x, double* penalty, double* dpenalty_dx); -/** Constrain lb <= min(v) <= ub. Namely all elements of the vector `v` returned -by the user-provided function to be no smaller than a specified minimum value -`lb`, and the minimal element of the vector is no larger than another specified -value `ub`. - -The formulation of the constraint is - -
-SmoothOverMax( φ((vᵢ - v_influence)/(v_influence - lb)) / φ(-1) ) ≤ 1
-SmoothUnderMax( φ((vᵢ - v_influence)/(v_influence - ub)) / φ(-1) ) ≥ 1
-
- -where vᵢ is the i-th value returned by the user-provided function, `lb` is -the minimum allowable value, `ub` is the upper bound for the min(v). (Note that -`ub` is NOT the upper bound of `v`). v_influence is the "influence value" (the -value below which an element influences the constraint or, conversely, the value -above which an element is ignored), φ is a solvers::MinimumValuePenaltyFunction, -and SmoothOverMax(v) is a smooth, over approximation of max(v) (i.e. -SmoothOverMax(v) >= max(v), for all v). SmoothUnderMax(x) is a smooth, under -approximation of max(v) (i.e. SmoothUnderMax(v) <= max(v) for all v). We require -that lb < ub < v_influence unless ub is infinity, in which case ub is ignored. -The input scaling (vᵢ - v_influence)/(v_influence - lb) ensures that at the -boundary of the feasible set (when vᵢ == lb), we evaluate the penalty function -at -1, where it is required to have a non-zero gradient. The user-provided -function may return a vector with up to `max_num_values` elements. If it returns -a vector with fewer than `max_num_values` elements, the remaining elements are -assumed to be greater than the "influence value". */ -class DRAKE_DEPRECATED( - "2024-02-01", - "Use MinimumValueLowerBoundConstraint if you want to constrain the minimum " - "value from below, and MinimumValueUpperBoundConstraint if you want to " - "constrain the minimum value from above.") MinimumValueConstraint final - : public solvers::Constraint { - public: - /** Constructs a MinimumValueConstraint. - min(v) >= lb - And we set ub to infinity in min(v) <= ub. - - @param num_vars The number of inputs to `value_function` - @param minimum_value The minimum allowed value, lb, for all elements - of the vector returned by `value_function`. - @param influence_value_offset The difference between the - influence value, v_influence, and the minimum value, lb (see class - documentation). This value must be finite and strictly positive, as it is used - to scale the values returned by `value_function`. Smaller values may - decrease the amount of computation required for each constraint evaluation if - `value_function` can quickly determine that some elements will be - larger than the influence value and skip the computation associated with those - elements. - @param max_num_values The maximum number of elements in the vector returned by - `value_function`. - @param value_function User-provided function that takes a `num_vars`-element - vector and the influence distance as inputs and returns a vector with up to - `max_num_values` elements. The function can omit from the return vector any - elements larger than the provided influence distance. - @param value_function_double Optional user-provide function that computes the - same values as `value_function` but for double rather than AutoDiffXd. If - omitted, `value_function` will be called (and the gradients discarded) when - this constraint is evaluated for doubles. - @pre `value_function_double(ExtractValue(x), v_influence) == - ExtractValue(value_function(x, v_influence))` for all x. - @pre `value_function(x).size() <= max_num_values` for all x. - @throws std::exception if influence_value_offset = ∞. - @throws std::exception if influence_value_offset ≤ 0. - */ - MinimumValueConstraint( - int num_vars, double minimum_value, double influence_value_offset, - int max_num_values, - std::function&, - double)> - value_function, - std::function(const Eigen::Ref>&, - double)> - value_function_double = {}); - - /** - Overloaded constructor. - This constructor allows to specify both the lower bound and upper bound of - the minimal element. - If you want to ignore the lower bound, then set `minimum_value_lower` to - -inf. Similary you can set `minimum_value_upper` to inf to ignore the upper - bound. But don't set both minimum_value_lower and minimum_value_upper to - infinity. - @param minimum_value_lower The minimum allowed value `lb`, for all - elements of the vector returned by `value_function`. - @param minimum_value_upper The upper bound on min(v), where `v` is the vector - returned by `value_function`. - @param influence_value This value must be finite and larger than both - `minimum_value_lower` and `minimum_value_upper`, as it is used to scale the - values returned by `value_function`. Smaller values may decrease the amount - of computation required for each constraint evaluation if `value_function` - can quickly determine that some elements will be larger than the influence - value and skip the computation associated with those elements. - */ - MinimumValueConstraint( - int num_vars, double minimum_value_lower, double minimum_value_upper, - double influence_value, int max_num_values, - std::function&, - double)> - value_function, - std::function(const Eigen::Ref>&, - double)> - value_function_double = {}); - - ~MinimumValueConstraint() override {} - - /** Getter for the lower bound on the minimum value. */ - double minimum_value_lower() const { return minimum_value_lower_; } - - /** Getter for the upper bound on the minimum value. */ - double minimum_value_upper() const { return minimum_value_upper_; } - - /** Getter for the influence value. */ - double influence_value() const { return influence_value_; } - - /** Getter for maximum number of values expected from value_function. */ - int max_num_values() const { return max_num_values_; } - - /** Setter for the penalty function. */ - void set_penalty_function(MinimumValuePenaltyFunction new_penalty_function); - - private: - // Given v, evaluate - // smooth_fun( φ((vᵢ - v_influence)/(v_influence - bound_value)) / φ(-1) ) - template - void EvalMaxPenalty( - double bound_value, const VectorX& values, int y_index, - const std::function&)>& smooth_func, - VectorX* y) const; - - template - void DoEvalGeneric(const Eigen::Ref>& x, - VectorX* y) const; - - void DoEval(const Eigen::Ref& x, - Eigen::VectorXd* y) const override; - - void DoEval(const Eigen::Ref& x, - AutoDiffVecXd* y) const override; - - void DoEval(const Eigen::Ref>&, - VectorX*) const override { - throw std::logic_error( - "MinimumValueConstraint::DoEval() does not work for symbolic " - "variables."); - } - - std::function value_function_; - std::function(const VectorX&, double)> - value_function_double_; - const double minimum_value_lower_; - const double minimum_value_upper_; - const double influence_value_; - /** Stores the value of - 1 / φ((vₘᵢₙ - v_influence)/(v_influence - vₘᵢₙ)) = 1 / φ(-1). This is - used to scale the output of the penalty function to be 1 when v == vₘᵢₙ. */ - double penalty_output_scaling_; - const int max_num_values_{}; - MinimumValuePenaltyFunction penalty_function_{}; -}; - /** Constrain min(v) >= lb where v=f(x). Namely all elements of the vector `v` returned by the user-provided function f(x) to be no smaller than a specified value `lb`. diff --git a/solvers/test/minimum_value_constraint_test.cc b/solvers/test/minimum_value_constraint_test.cc index 62b40e5d8b7a..49e9dd3bcee3 100644 --- a/solvers/test/minimum_value_constraint_test.cc +++ b/solvers/test/minimum_value_constraint_test.cc @@ -15,7 +15,7 @@ namespace { const double kInf = std::numeric_limits::infinity(); -double kEps{std::numeric_limits::epsilon()}; +const double kEps = std::numeric_limits::epsilon(); // Returns the element-wise square of it's input. template @@ -47,303 +47,6 @@ VectorX ReturnNoValues(const Eigen::Ref>&, double) { return VectorX(0); } -// Verify that the constructor works as expected. -#pragma GCC diagnostic push -#pragma GCC diagnostic ignored "-Wdeprecated-declarations" -GTEST_TEST(MinimumValueConstraintTests, ConstructorTest1) { - // Constructor with only minimum_value_lower - int expected_num_vars{5}; - int expected_max_num_values{3}; - double expected_minimum_value{0.1}; - double expected_influence_value{0.2}; - MinimumValueConstraint dut(expected_num_vars, expected_minimum_value, - expected_influence_value - expected_minimum_value, - expected_max_num_values, - &SquareAndReturnAll); - EXPECT_EQ(dut.num_vars(), expected_num_vars); - EXPECT_EQ(dut.max_num_values(), expected_max_num_values); - EXPECT_EQ(dut.minimum_value_lower(), expected_minimum_value); - EXPECT_EQ(dut.minimum_value_upper(), kInf); - EXPECT_EQ(dut.influence_value(), expected_influence_value); - EXPECT_EQ(dut.num_constraints(), 1); - EXPECT_EQ(dut.upper_bound()(0), 1); - EXPECT_EQ(dut.lower_bound()(0), -kInf); -} - -GTEST_TEST(MinimumValueConstraintTest, ConstructorTest2) { - // Constructor with only minimum_value_upper - int expected_num_vars{5}; - int expected_max_num_values{3}; - double expected_minimum_value{0.1}; - double expected_influence_value{0.2}; - - MinimumValueConstraint dut(expected_num_vars, -kInf, expected_minimum_value, - expected_influence_value, expected_max_num_values, - &SquareAndReturnAll); - EXPECT_EQ(dut.num_vars(), expected_num_vars); - EXPECT_EQ(dut.max_num_values(), expected_max_num_values); - EXPECT_FALSE(std::isfinite(dut.minimum_value_lower())); - EXPECT_EQ(dut.minimum_value_upper(), expected_minimum_value); - EXPECT_EQ(dut.influence_value(), expected_influence_value); - EXPECT_EQ(dut.num_constraints(), 1); - EXPECT_EQ(dut.lower_bound()(0), 1); - EXPECT_FALSE(std::isfinite(dut.upper_bound()(0))); -} - -GTEST_TEST(MinimumValueConstraintTest, ConstructorTest3) { - // Constructor with both minimum_value_lower and minimum_value_upper - int expected_num_vars{5}; - int expected_max_num_values{3}; - const double minimum_value_lower{0.05}; - const double minimum_value_upper{0.1}; - double expected_influence_value{0.2}; - - MinimumValueConstraint dut(expected_num_vars, minimum_value_lower, - minimum_value_upper, expected_influence_value, - expected_max_num_values, - &SquareAndReturnAll); - EXPECT_EQ(dut.num_vars(), expected_num_vars); - EXPECT_EQ(dut.max_num_values(), expected_max_num_values); - EXPECT_EQ(dut.minimum_value_lower(), minimum_value_lower); - EXPECT_EQ(dut.minimum_value_upper(), minimum_value_upper); - EXPECT_EQ(dut.influence_value(), expected_influence_value); - EXPECT_EQ(dut.num_constraints(), 2); - EXPECT_TRUE(CompareMatrices(dut.lower_bound(), Eigen::Vector2d(-kInf, 1))); - EXPECT_TRUE(CompareMatrices(dut.upper_bound(), Eigen::Vector2d(1, kInf))); -} - -// Verify that the non-symbolic versions of Eval() behave as expected. -GTEST_TEST(MinimumValueConstraintTests, EvalNonsymbolicTest1) { - // The constraint is constructed only with the lower bound on its minimal - // value, no upper bound. - int num_vars{5}; - int max_num_values{5}; - double minimum_value{0.1}; - double influence_value{0.2}; - MinimumValueConstraint dut_return_all( - num_vars, minimum_value, influence_value - minimum_value, max_num_values, - &SquareAndReturnAll, &SquareAndReturnAll); - MinimumValueConstraint dut_return_less_than_influence_value( - num_vars, minimum_value, influence_value - minimum_value, max_num_values, - &SquareAndReturnLessThanInfluenceValue); - double tol = kEps; - AutoDiffVecXd x_0 = AutoDiffVecXd::Zero(num_vars); - AutoDiffVecXd x_0_to_twice_sqrt_influence_value = - AutoDiffVecXd::LinSpaced(num_vars, 0, 2 * std::sqrt(influence_value)); - AutoDiffVecXd x_sqrt_min_value_to_twice_sqrt_influence_value = - AutoDiffVecXd::LinSpaced(num_vars, std::sqrt(minimum_value), - 2 * std::sqrt(influence_value)); - auto check_constraints = [&](std::vector inputs, - bool should_constraints_be_satisfied) { - for (const AutoDiffVecXd& x : inputs) { - test::CheckConstraintEvalNonsymbolic(dut_return_all, x, tol); - test::CheckConstraintEvalNonsymbolic(dut_return_less_than_influence_value, - x, tol); - AutoDiffVecXd y_return_all, y_return_less_than_influence_value; - dut_return_all.Eval(x, &y_return_all); - dut_return_less_than_influence_value.Eval( - x, &y_return_less_than_influence_value); - ASSERT_EQ(y_return_all.size(), 1); - ASSERT_EQ(y_return_less_than_influence_value.size(), 1); - EXPECT_EQ(y_return_all(0), y_return_less_than_influence_value(0)); - EXPECT_EQ(dut_return_all.CheckSatisfied(x, kEps), - should_constraints_be_satisfied); - EXPECT_EQ(dut_return_less_than_influence_value.CheckSatisfied(x, kEps), - should_constraints_be_satisfied); - } - }; - // Check with inputs that should violate the constraints. - check_constraints({x_0, x_0_to_twice_sqrt_influence_value, - x_sqrt_min_value_to_twice_sqrt_influence_value - - AutoDiffVecXd::Constant(num_vars, kEps)}, - false); - // Check with inputs that should satisfy the constraints. - check_constraints({x_sqrt_min_value_to_twice_sqrt_influence_value}, true); - - // All value are larger than influence_value. - AutoDiffVecXd x_sqrt_influence_value_to_twice_sqrt_influence_value = - AutoDiffVecXd::LinSpaced(num_vars, 1.1 * std::sqrt(influence_value), - 2 * std::sqrt(influence_value)); - check_constraints({x_sqrt_influence_value_to_twice_sqrt_influence_value}, - true); -} - -// Verify that the non-symbolic versions of Eval() behave as expected. -GTEST_TEST(MinimumValueConstraintTests, EvalNonsymbolicTest2) { - // The constraint is constructed only with the upper bound on its minimal - // value, no lower bound. - int num_vars{5}; - int max_num_values{5}; - double minimum_value_lower{-kInf}; - double minimum_value_upper{0.1}; - double influence_value{0.2}; - MinimumValueConstraint dut_return_all( - num_vars, minimum_value_lower, minimum_value_upper, influence_value, - max_num_values, &SquareAndReturnAll, - &SquareAndReturnAll); - MinimumValueConstraint dut_return_less_than_influence_value( - num_vars, minimum_value_lower, minimum_value_upper, influence_value, - max_num_values, &SquareAndReturnLessThanInfluenceValue); - double tol = kEps; - AutoDiffVecXd x_0 = AutoDiffVecXd::Zero(num_vars); - AutoDiffVecXd x_0_to_twice_sqrt_influence_value = - AutoDiffVecXd::LinSpaced(num_vars, 0, 2 * std::sqrt(influence_value)); - AutoDiffVecXd x_sqrt_min_value_to_twice_sqrt_influence_value = - AutoDiffVecXd::LinSpaced(num_vars, std::sqrt(minimum_value_upper), - 2 * std::sqrt(influence_value)); - AutoDiffVecXd x_sqrt_min_value_plus_eps_to_twice_sqrt_influence_value = - AutoDiffVecXd::LinSpaced(num_vars, std::sqrt(minimum_value_upper + 0.01), - 2 * std::sqrt(influence_value)); - auto check_constraints = [&](std::vector inputs, - bool should_constraints_be_satisfied) { - for (const AutoDiffVecXd& x : inputs) { - test::CheckConstraintEvalNonsymbolic(dut_return_all, x, tol); - test::CheckConstraintEvalNonsymbolic(dut_return_less_than_influence_value, - x, tol); - AutoDiffVecXd y_return_all, y_return_less_than_influence_value; - dut_return_all.Eval(x, &y_return_all); - dut_return_less_than_influence_value.Eval( - x, &y_return_less_than_influence_value); - ASSERT_EQ(y_return_all.size(), 1); - ASSERT_EQ(y_return_less_than_influence_value.size(), 1); - EXPECT_EQ(y_return_all(0), y_return_less_than_influence_value(0)); - EXPECT_EQ(dut_return_all.CheckSatisfied(x, kEps), - should_constraints_be_satisfied); - EXPECT_EQ(dut_return_less_than_influence_value.CheckSatisfied(x, kEps), - should_constraints_be_satisfied); - } - }; - // Check with inputs that should satisfy the constraints. - check_constraints({x_0, x_0_to_twice_sqrt_influence_value, - x_sqrt_min_value_to_twice_sqrt_influence_value - - AutoDiffVecXd::Constant(num_vars, kEps)}, - true); - // Check with inputs that is on the boundary of satisfying the constraints. - check_constraints({x_sqrt_min_value_to_twice_sqrt_influence_value}, true); - // Check with inputs that should violate the constraints. - check_constraints({x_sqrt_min_value_plus_eps_to_twice_sqrt_influence_value}, - false); - // All value are larger than influence_value. - AutoDiffVecXd x_sqrt_influence_value_to_twice_sqrt_influence_value = - AutoDiffVecXd::LinSpaced(num_vars, 1.1 * std::sqrt(influence_value), - 2 * std::sqrt(influence_value)); - check_constraints({x_sqrt_influence_value_to_twice_sqrt_influence_value}, - false); - - // Now make sure the gradient is continuous across influence_value. - const AutoDiffVecXd x_below_influence = - math::InitializeAutoDiff(Eigen::VectorXd::LinSpaced( - num_vars, std::sqrt(minimum_value_upper * 0.99), - std::sqrt(influence_value - 1E-5))); - AutoDiffVecXd x_above_influence = x_below_influence; - x_above_influence(num_vars - 1).value() = std::sqrt(influence_value + 1E-5); - AutoDiffVecXd y_below_influence; - AutoDiffVecXd y_above_influence; - for (const auto* constraint : - {&dut_return_all, &dut_return_less_than_influence_value}) { - constraint->Eval(x_below_influence, &y_below_influence); - constraint->Eval(x_above_influence, &y_above_influence); - EXPECT_NEAR(y_below_influence(0).value(), y_above_influence(0).value(), - 1E-10); - EXPECT_TRUE(CompareMatrices(y_below_influence(0).derivatives(), - y_above_influence(0).derivatives(), 1E-10)); - } -} - -// Verify that the non-symbolic versions of Eval() behave as expected. -GTEST_TEST(MinimumValueConstraintTests, EvalNonsymbolicTest3) { - // The constraint is constructed with both the lower and the upper bound on - // its minimal value. - int num_vars{5}; - int max_num_values{5}; - double minimum_value_lower{0.05}; - double minimum_value_upper{0.1}; - double influence_value{0.2}; - MinimumValueConstraint dut_return_all( - num_vars, minimum_value_lower, minimum_value_upper, influence_value, - max_num_values, &SquareAndReturnAll, - &SquareAndReturnAll); - MinimumValueConstraint dut_return_less_than_influence_value( - num_vars, minimum_value_lower, minimum_value_upper, influence_value, - max_num_values, &SquareAndReturnLessThanInfluenceValue); - double tol = kEps; - AutoDiffVecXd x_0 = AutoDiffVecXd::Zero(num_vars); - AutoDiffVecXd x_0_to_twice_sqrt_influence_value = - AutoDiffVecXd::LinSpaced(num_vars, 0, 2 * std::sqrt(influence_value)); - AutoDiffVecXd x_sqrt_min_value_to_twice_sqrt_influence_value = - AutoDiffVecXd::LinSpaced(num_vars, std::sqrt(minimum_value_lower), - 2 * std::sqrt(influence_value)); - auto check_constraints = [&](std::vector inputs, - bool should_constraints_be_satisfied) { - for (const AutoDiffVecXd& x : inputs) { - test::CheckConstraintEvalNonsymbolic(dut_return_all, x, tol); - test::CheckConstraintEvalNonsymbolic(dut_return_less_than_influence_value, - x, tol); - AutoDiffVecXd y_return_all, y_return_less_than_influence_value; - dut_return_all.Eval(x, &y_return_all); - dut_return_less_than_influence_value.Eval( - x, &y_return_less_than_influence_value); - ASSERT_EQ(y_return_all.size(), 2); - ASSERT_EQ(y_return_less_than_influence_value.size(), 2); - EXPECT_EQ(y_return_all(0), y_return_less_than_influence_value(0)); - EXPECT_EQ(y_return_all(1), y_return_less_than_influence_value(1)); - EXPECT_EQ(dut_return_all.CheckSatisfied(x, kEps), - should_constraints_be_satisfied); - EXPECT_EQ(dut_return_less_than_influence_value.CheckSatisfied(x, kEps), - should_constraints_be_satisfied); - } - }; - // Check with inputs that should violate the constraints. - check_constraints({x_0, x_0_to_twice_sqrt_influence_value, - x_sqrt_min_value_to_twice_sqrt_influence_value - - AutoDiffVecXd::Constant(num_vars, kEps)}, - false); - // Check with inputs that is should satisfy the constraints. - check_constraints({x_sqrt_min_value_to_twice_sqrt_influence_value}, true); -} - -GTEST_TEST(MinimumValueConstraintTests, EvalNoValuesTest1) { - // Test with only lower bound on the minimal value, no upper bound. - int num_vars{5}; - int max_num_values{0}; - double minimum_value{0.1}; - double influence_value{0.2}; - MinimumValueConstraint dut_no_values( - num_vars, minimum_value, influence_value - minimum_value, max_num_values, - &ReturnNoValues); - test::CheckConstraintEvalNonsymbolic(dut_no_values, - AutoDiffVecXd::Zero(num_vars), kEps); -} - -GTEST_TEST(MinimumValueConstraintTests, EvalNoValuesTest2) { - // Test with both the lower and the upper bound on the minimal value. - int num_vars{5}; - int max_num_values{0}; - double minimum_value_lower{0.05}; - double minimum_value_upper{0.1}; - double influence_value{0.2}; - MinimumValueConstraint dut_no_values( - num_vars, minimum_value_lower, minimum_value_upper, influence_value, - max_num_values, &ReturnNoValues); - test::CheckConstraintEvalNonsymbolic(dut_no_values, - AutoDiffVecXd::Zero(num_vars), kEps); -} - -// Verify that Eval() throws for symbolic inputs. -GTEST_TEST(MinimumValueConstraintTests, EvalSymbolicTest) { - int num_vars{5}; - int max_num_values{5}; - double minimum_value{0.1}; - double influence_value{0.2}; - MinimumValueConstraint dut(num_vars, minimum_value, - influence_value - minimum_value, max_num_values, - &SquareAndReturnAll); - VectorX x{num_vars}; - VectorX y; - EXPECT_THROW(dut.Eval(x, &y), std::logic_error); -} -#pragma GCC diagnostic pop - // Verify that the constructor works as expected. GTEST_TEST(MinimumValueLowerBoundConstraintTests, ConstructorTest) { // Constructor with only minimum_value_lower diff --git a/systems/analysis/simulator.h b/systems/analysis/simulator.h index a0b7f2655ab5..1c23bc276912 100644 --- a/systems/analysis/simulator.h +++ b/systems/analysis/simulator.h @@ -540,8 +540,7 @@ class Simulator { /// Specifically, that means the System::Publish() event dispatcher will be /// invoked on each subsystem of the System and passed the current Context /// and a forced-publish Event. If a subsystem has declared a forced-publish - /// event handler, that will be called. Otherwise, nothing will happen unless - /// the DoPublish() dispatcher has been overridden. + /// event handler, that will be called. Otherwise, nothing will happen. /// /// Enabling this option does not cause a forced-publish to be triggered at /// initialization; if you want that you should also call diff --git a/systems/analysis/simulator_config_functions.h b/systems/analysis/simulator_config_functions.h index 5f07cae33431..f5b46916d165 100644 --- a/systems/analysis/simulator_config_functions.h +++ b/systems/analysis/simulator_config_functions.h @@ -4,7 +4,6 @@ #include #include "drake/common/default_scalars.h" -#include "drake/common/drake_deprecated.h" #include "drake/systems/analysis/integrator_base.h" #include "drake/systems/analysis/simulator.h" #include "drake/systems/analysis/simulator_config.h" diff --git a/systems/analysis/test/simulator_test.cc b/systems/analysis/test/simulator_test.cc index 837ba156aedf..e843d92acbff 100644 --- a/systems/analysis/test/simulator_test.cc +++ b/systems/analysis/test/simulator_test.cc @@ -1417,17 +1417,21 @@ class UnrestrictedUpdater : public LeafSystem { double* time) const override { const double inf = std::numeric_limits::infinity(); *time = (context.get_time() < t_upd_) ? t_upd_ : inf; - UnrestrictedUpdateEvent event( - TriggerType::kPeriodic); - event.AddToComposite(event_info); - } - - void DoCalcUnrestrictedUpdate( - const Context& context, - const std::vector*>& events, - State* state) const override { - if (unrestricted_update_callback_ != nullptr) - unrestricted_update_callback_(context, state); + if (unrestricted_update_callback_ != nullptr) { + UnrestrictedUpdateEvent event( + TriggerType::kPeriodic, + [callback = unrestricted_update_callback_]( + const System&, const Context& event_context, + const UnrestrictedUpdateEvent&, + State* event_state) { + callback(event_context, event_state); + return EventStatus::Succeeded(); + }); + event.AddToComposite(event_info); + } else { + UnrestrictedUpdateEvent event(TriggerType::kPeriodic); + event.AddToComposite(event_info); + } } void DoCalcTimeDerivatives( diff --git a/systems/controllers/inverse_dynamics_controller.h b/systems/controllers/inverse_dynamics_controller.h index 11c98c49816f..dd908848101f 100644 --- a/systems/controllers/inverse_dynamics_controller.h +++ b/systems/controllers/inverse_dynamics_controller.h @@ -6,7 +6,6 @@ #include "drake/common/default_scalars.h" #include "drake/common/drake_copyable.h" -#include "drake/common/drake_deprecated.h" #include "drake/multibody/plant/multibody_plant.h" #include "drake/systems/controllers/inverse_dynamics.h" #include "drake/systems/controllers/pid_controller.h" diff --git a/systems/framework/abstract_values.h b/systems/framework/abstract_values.h index e28012c83413..9286322a3221 100644 --- a/systems/framework/abstract_values.h +++ b/systems/framework/abstract_values.h @@ -5,7 +5,6 @@ #include "drake/common/drake_assert.h" #include "drake/common/drake_copyable.h" -#include "drake/common/drake_deprecated.h" #include "drake/common/value.h" namespace drake { diff --git a/systems/framework/context_base.h b/systems/framework/context_base.h index c9e373a3803c..177c63350b99 100644 --- a/systems/framework/context_base.h +++ b/systems/framework/context_base.h @@ -256,19 +256,6 @@ class ContextBase : public internal::ContextMessageInterface { /** Returns true if this context has no parent. */ bool is_root_context() const { return parent_ == nullptr; } -#ifndef DRAKE_DOXYGEN_CXX - // (Internal use only) Provides a mutable flag for use in deprecating - // user-overrideable virtuals in Drake code that only has access to a const - // Context. There is no explicit thread safety provided, but this can be used - // in a thread-safe manner as long as Contexts are not shared among threads. - void set_use_default_implementation(bool value) const { - use_default_implementation_ = value; - } - bool get_use_default_implementation() const { - return use_default_implementation_; - } -#endif - protected: /** Default constructor creates an empty ContextBase but initializes all the built-in dependency trackers that are the same in every System (like time, @@ -667,9 +654,6 @@ class ContextBase : public internal::ContextMessageInterface { // Note that it does *not* get reset when copied. mutable int64_t current_change_event_{0}; - // A writable flag for use in deprecating user-overrideable virtuals. - mutable bool use_default_implementation_{false}; - // This is the dependency graph for values within this subcontext. DependencyGraph graph_; diff --git a/systems/framework/discrete_values.h b/systems/framework/discrete_values.h index a2ba857665e2..42dbf2771896 100644 --- a/systems/framework/discrete_values.h +++ b/systems/framework/discrete_values.h @@ -9,7 +9,6 @@ #include "drake/common/default_scalars.h" #include "drake/common/drake_assert.h" #include "drake/common/drake_copyable.h" -#include "drake/common/drake_deprecated.h" #include "drake/common/drake_throw.h" #include "drake/common/value.h" #include "drake/systems/framework/basic_vector.h" diff --git a/systems/framework/event.h b/systems/framework/event.h index 2a908539d081..fecc33e73e36 100644 --- a/systems/framework/event.h +++ b/systems/framework/event.h @@ -114,11 +114,8 @@ template class System; #### Declaring update functions - The preferred way to update state through events is to declare an update - handler in your LeafSystem-derived-class. Some older Drake code computes - state updates by overriding event dispatchers (e.g., - LeafSystem::DoCalcUnrestrictedUpdate()), **though that practice is discouraged - and will soon be deprecated.** + The way to update state through events is to declare an update handler in your + LeafSystem-derived-class. A number of convenience functions are available in LeafSystem for declaring various trigger and event update combinations; see, e.g., diff --git a/systems/framework/event_collection.h b/systems/framework/event_collection.h index ff278ead0417..cb369a9351aa 100644 --- a/systems/framework/event_collection.h +++ b/systems/framework/event_collection.h @@ -24,25 +24,9 @@ namespace systems { * abstract base class that stores simultaneous events *of the same type* that * occur *at the same time* (i.e., simultaneous events). * - * For each concrete event type, the LeafSystem API provides a unique - * customizable function for processing all simultaneous events of that type, - * e.g. - * LeafSystem::DoPublish(const Context&, const vector&) - * for publish events, where the second argument represents all of the publish - * events that occur simultaneously for that leaf system. The default - * implementation processes the events (i.e., call their callback functions) - * in the order in which they are stored in the second argument. - * The developer of new classes derived from LeafSystem is responsible for - * overriding such functions if the custom LeafSystem behavior depends on the - * order in which events are processed. For example, suppose two publish events - * are being processed, `events = {per-step publish, periodic publish}`. - * Depending on the desired behavior, the developer has the freedom to ignore - * both events, perform only one publish action, or perform both publish actions - * in any arbitrary order. The System and Diagram API provide only dispatch - * mechanisms that delegate actual event handling to the - * constituent leaf systems. The Simulator promises that for each set of - * simultaneous events of the same type, the public event handling method - * (e.g. System::Publish(context, publish_events)) will be invoked exactly once. + * The Simulator promises that for each set of simultaneous events of the same + * type, the public event handling method (e.g., + * System::Publish(context, publish_events)) will be invoked exactly once. * * The System API provides several functions for customizable event generation * such as System::DoCalcNextUpdateTime() or System::DoGetPerStepEvents(). @@ -86,13 +70,6 @@ namespace systems { * all_events.get_discrete_update_events(), discrete_state); * sys.Publish(context, all_events.get_publish_events()) * - * For a LeafSystem, this is equivalent to (by expanding the dispatch mechanisms - * in the System API): - *
- *   sys.DoCalcUnrestrictedUpdate(context, {event4}, state);
- *   sys.DoCalcDiscreteVariableUpdates(context, {event2}, discrete_state);
- *   sys.DoPublish(context, {event1, event3})
- * 
* * @tparam EventType a concrete derived type of Event (e.g., PublishEvent). */ diff --git a/systems/framework/fixed_input_port_value.h b/systems/framework/fixed_input_port_value.h index db2c1ebd123f..8f71ee0125e6 100644 --- a/systems/framework/fixed_input_port_value.h +++ b/systems/framework/fixed_input_port_value.h @@ -8,7 +8,6 @@ #include "drake/common/copyable_unique_ptr.h" #include "drake/common/drake_copyable.h" -#include "drake/common/drake_deprecated.h" #include "drake/common/reset_on_copy.h" #include "drake/common/value.h" #include "drake/systems/framework/basic_vector.h" diff --git a/systems/framework/framework_common.h b/systems/framework/framework_common.h index 045adb167c12..4c3584e62107 100644 --- a/systems/framework/framework_common.h +++ b/systems/framework/framework_common.h @@ -9,7 +9,6 @@ #include #include "drake/common/drake_assert.h" -#include "drake/common/drake_deprecated.h" #include "drake/common/identifier.h" #include "drake/common/type_safe_index.h" #include "drake/common/value.h" diff --git a/systems/framework/leaf_system.cc b/systems/framework/leaf_system.cc index 93053523d7dd..1ea4d7fe2475 100644 --- a/systems/framework/leaf_system.cc +++ b/systems/framework/leaf_system.cc @@ -5,7 +5,6 @@ #include "absl/container/inlined_vector.h" -#include "drake/common/drake_deprecated.h" #include "drake/common/pointer_cast.h" #include "drake/systems/framework/system_symbolic_inspector.h" #include "drake/systems/framework/value_checker.h" @@ -468,24 +467,6 @@ int LeafSystem::DeclareAbstractParameter(const AbstractValue& model_value) { return index; } -template -void LeafSystem::DeclarePeriodicPublishNoHandler( - double period_sec, double offset_sec) { - DeclarePeriodicEvent(period_sec, offset_sec, PublishEvent()); -} - -template -void LeafSystem::DeclarePeriodicDiscreteUpdateNoHandler( - double period_sec, double offset_sec) { - DeclarePeriodicEvent(period_sec, offset_sec, DiscreteUpdateEvent()); -} - -template -void LeafSystem::DeclarePeriodicUnrestrictedUpdateNoHandler( - double period_sec, double offset_sec) { - DeclarePeriodicEvent(period_sec, offset_sec, UnrestrictedUpdateEvent()); -} - template ContinuousStateIndex LeafSystem::DeclareContinuousState( int num_state_variables) { @@ -740,37 +721,6 @@ SystemConstraintIndex LeafSystem::DeclareInequalityConstraint( this, std::move(calc), std::move(bounds), std::move(description))); } -template -void LeafSystem::DoPublish( - const Context& context, - const std::vector*>&) const { - // Sets this flag to indicate that the derived System did not override - // our default method. See DispatchPublishHandler() for how this is used. - context.set_use_default_implementation(true); -} - -template -void LeafSystem::DoCalcDiscreteVariableUpdates( - const Context& context, - const std::vector*>&, - DiscreteValues*) const { - // Sets this flag to indicate that the derived System did not override - // our default method. See DispatchDiscreteVariableUpdateHandler() for how - // this is used. - context.set_use_default_implementation(true); -} - -template -void LeafSystem::DoCalcUnrestrictedUpdate( - const Context& context, - const std::vector*>&, - State*) const { - // Sets this flag to indicate that the derived System did not override - // our default method. See DispatchUnrestrictedUpdateHandler() for how - // this is used. - context.set_use_default_implementation(true); -} - template std::unique_ptr LeafSystem::DoAllocateInput( const InputPort& input_port) const { @@ -826,30 +776,13 @@ EventStatus LeafSystem::DispatchPublishHandler( // This function shouldn't have been called if no publish events. DRAKE_DEMAND(leaf_events.HasEvents()); - // Determine whether the derived System overloaded DoPublish(). If so, this - // flag will remain false; the default implementation sets it to true. - context.set_use_default_implementation(false); -#pragma GCC diagnostic push -#pragma GCC diagnostic ignored "-Wdeprecated-declarations" - this->DoPublish(context, leaf_events.get_events()); -#pragma GCC diagnostic pop - if (!context.get_use_default_implementation()) { - static const drake::internal::WarnDeprecated warn_once( - "2024-02-01", - "Overriding LeafSystem::DoPublish is deprecated."); - // Derived system overrode the dispatcher and did not invoke the base class - // implementation so there is nothing else to do. - return EventStatus::Succeeded(); - } - - // Use our default dispatch policy. EventStatus overall_status = EventStatus::DidNothing(); for (const PublishEvent* event : leaf_events.get_events()) { const EventStatus per_event_status = event->handle(*this, context); overall_status.KeepMoreSevere(per_event_status); - // Unlike the discrete & unrestricted event policy, we don't stop - // handling publish events when one fails; we just report the first failure - // after all the publishes are done. + // Unlike the discrete & unrestricted event policy, we don't stop handling + // publish events when one fails; we just report the first failure after all + // the publishes are done. } return overall_status; } @@ -868,25 +801,6 @@ EventStatus LeafSystem::DispatchDiscreteVariableUpdateHandler( // Must initialize the output argument with current discrete state contents. discrete_state->SetFrom(context.get_discrete_state()); - // Determine whether the derived System overloaded - // DoCalcDiscreteVariableUpdates(). If so, this flag will remain false; the - // default implementation sets it to true. - context.set_use_default_implementation(false); -#pragma GCC diagnostic push -#pragma GCC diagnostic ignored "-Wdeprecated-declarations" - this->DoCalcDiscreteVariableUpdates(context, leaf_events.get_events(), - discrete_state); // in/out -#pragma GCC diagnostic pop - if (!context.get_use_default_implementation()) { - static const drake::internal::WarnDeprecated warn_once( - "2024-02-01", - "Overriding LeafSystem::DoCalcDiscreteVariableUpdates is deprecated."); - // Derived system overrode the dispatcher and did not invoke the base class - // implementation so there is nothing else to do. - return EventStatus::Succeeded(); - } - - // Use our default dispatch policy. EventStatus overall_status = EventStatus::DidNothing(); for (const DiscreteUpdateEvent* event : leaf_events.get_events()) { const EventStatus per_event_status = @@ -921,27 +835,11 @@ EventStatus LeafSystem::DispatchUnrestrictedUpdateHandler( DRAKE_DEMAND(leaf_events.HasEvents()); // Must initialize the output argument with current state contents. + // TODO(sherm1) Shouldn't require preloading of the output state; better to + // note just the changes since usually only a small subset will be changed by + // the callback function. state->SetFrom(context.get_state()); - // Determine whether the derived System overloaded - // DoCalcUnrestrictedUpdate(). If so, this flag will remain false; the - // default implementation sets it to true. - context.set_use_default_implementation(false); -#pragma GCC diagnostic push -#pragma GCC diagnostic ignored "-Wdeprecated-declarations" - this->DoCalcUnrestrictedUpdate(context, leaf_events.get_events(), - state); // in/out -#pragma GCC diagnostic pop - if (!context.get_use_default_implementation()) { - static const drake::internal::WarnDeprecated warn_once( - "2024-02-01", - "Overriding LeafSystem::DoCalcUnrestrictedUpdate is deprecated."); - // Derived system overrode the dispatcher and did not invoke the base class - // implementation so there is nothing else to do. - return EventStatus::Succeeded(); - } - - // Use our default dispatch policy. EventStatus overall_status = EventStatus::DidNothing(); for (const UnrestrictedUpdateEvent* event : leaf_events.get_events()) { const EventStatus per_event_status = event->handle(*this, context, state); diff --git a/systems/framework/leaf_system.h b/systems/framework/leaf_system.h index 8dbdeaeda7aa..3231a988b17e 100644 --- a/systems/framework/leaf_system.h +++ b/systems/framework/leaf_system.h @@ -14,7 +14,6 @@ #include "drake/common/default_scalars.h" #include "drake/common/drake_assert.h" #include "drake/common/drake_copyable.h" -#include "drake/common/drake_deprecated.h" #include "drake/common/eigen_types.h" #include "drake/common/unused.h" #include "drake/common/value.h" @@ -485,27 +484,6 @@ class LeafSystem : public System { event_copy->set_event_data(periodic_data); event_copy->AddToComposite(TriggerType::kPeriodic, &periodic_events_); } - - DRAKE_DEPRECATED( - "2024-02-01", - "Overriding DoPublish is no longer allowed. " - "Use DeclarePeriodicPublishEvent() instead.") - void DeclarePeriodicPublishNoHandler(double period_sec, - double offset_sec = 0); - - DRAKE_DEPRECATED( - "2024-02-01", - "Overriding DoCalcDiscreteVariableUpdates is no longer allowed. " - "Use DeclarePeriodicDiscreteUpdateEvent() instead.") - void DeclarePeriodicDiscreteUpdateNoHandler(double period_sec, - double offset_sec = 0); - - DRAKE_DEPRECATED( - "2024-02-01", - "Overriding DoCalcUnrestrictedUpdate is no longer allowed. " - "Use DeclarePeriodicUnrestrictedUpdateEvent() instead.") - void DeclarePeriodicUnrestrictedUpdateNoHandler(double period_sec, - double offset_sec = 0); //@} // ========================================================================= @@ -1783,116 +1761,6 @@ class LeafSystem : public System { SystemConstraintBounds bounds, std::string description); - DRAKE_DEPRECATED( - "2024-02-01", - "Overriding DoPublish is no longer allowed") - /** Derived-class event dispatcher for all simultaneous publish events - in @p events. Override this in your derived LeafSystem only if you require - behavior other than the default dispatch behavior (not common). - The default behavior is to traverse events in the arbitrary order they - appear in @p events, and for each event that has a callback function, - to invoke the callback with @p context and that event. - - Do not override this just to handle an event -- instead declare the event - and a handler callback for it using one of the `Declare...PublishEvent()` - methods. - - This method is called only from the virtual DispatchPublishHandler, which - is only called from the public non-virtual Publish(), which will have - already error-checked @p context so you may assume that it is valid. - - @note There is no provision for returning EventStatus from DoPublish() as - there is if you use the default dispatcher. Instead, your DoPublish() will be - assumed to return EventStatus::Succeeded() regardless of what happened. - - @param[in] context Const current context. - @param[in] events All the publish events that need handling. */ - virtual void DoPublish( - const Context& context, - const std::vector*>& events) const; - - DRAKE_DEPRECATED( - "2024-02-01", - "Overriding DoCalcDiscreteVariableUpdates is no longer allowed") - /** Derived-class event dispatcher for all simultaneous discrete update - events. Override this in your derived LeafSystem only if you require - behavior other than the default dispatch behavior (not common). - The default behavior is to traverse events in the arbitrary order they - appear in @p events, and for each event that has a callback function, - to invoke the callback with @p context, that event, and @p discrete_state. - Note that the same (possibly modified) @p discrete_state is passed to - subsequent callbacks. - - Do not override this just to handle an event -- instead declare the event - and a handler callback for it using one of the - `Declare...DiscreteUpdateEvent()` methods. - - This method is called only from the virtual - DispatchDiscreteVariableUpdateHandler(), which is only called from - the public non-virtual CalcDiscreteVariableUpdate(), which will already - have error-checked the parameters so you don't have to. In particular, - implementations may assume that @p context is valid; that - @p discrete_state is non-null, and that the referenced object has the - same constituent structure as was produced by AllocateDiscreteVariables(). - - @note There is no provision for returning EventStatus from - DoCalcDiscreteVariableUpdates() as there is if you use the default - dispatcher. Instead, your DoCalcDiscreteVariableUpdates() will be assumed to - return EventStatus::Succeeded() regardless of what happened. - - @param[in] context The "before" state. - @param[in] events All the discrete update events that need handling. - @param[in,out] discrete_state The current state of the system on input; - the desired state of the system on return. */ - virtual void DoCalcDiscreteVariableUpdates( - const Context& context, - const std::vector*>& events, - DiscreteValues* discrete_state) const; - - // TODO(sherm1) Shouldn't require preloading of the output state; better to - // note just the changes since usually only a small subset will - // be changed by this method. - - DRAKE_DEPRECATED( - "2024-02-01", - "Overriding DoCalcUnrestrictedUpdate is no longer allowed") - /** Derived-class event dispatcher for all simultaneous unrestricted update - events. Override this in your derived LeafSystem only if you require - behavior other than the default dispatch behavior (not common). - The default behavior is to traverse events in the arbitrary order they - appear in @p events, and for each event that has a callback function, - to invoke the callback with @p context, that event, and @p state. - Note that the same (possibly modified) @p state is passed to subsequent - callbacks. - - Do not override this just to handle an event -- instead declare the event - and a handler callback for it using one of the - `Declare...UnrestrictedUpdateEvent()` methods. - - This method is called only from the virtual - DispatchUnrestrictedUpdateHandler(), which is only called from the - non-virtual public CalcUnrestrictedUpdate(), which will already have - error-checked the parameters so you don't have to. In particular, - implementations may assume that the @p context is valid; that @p state - is non-null, and that the referenced object has the same constituent - structure as the state in @p context. - - @note There is no provision for returning EventStatus from - DoCalcUnrestrictedUpdate() as there is if you use the default dispatcher. - Instead, your DoCalcUnrestrictedUpdate() will be assumed to return - EventStatus::Succeeded() regardless of what happened. - - @param[in] context The "before" state that is to be used to calculate - the returned state update. - @param[in] events All the unrestricted update events that need - handling. - @param[in,out] state The current state of the system on input; the - desired state of the system on return. */ - virtual void DoCalcUnrestrictedUpdate( - const Context& context, - const std::vector*>& events, - State* state) const; - private: using SystemBase::NextInputPortName; using SystemBase::NextOutputPortName; @@ -1914,7 +1782,6 @@ class LeafSystem : public System { std::optional* timing, EventCollection>* events) const final; - // Calls DoPublish. // Assumes @param events is an instance of LeafEventCollection, throws // std::bad_cast otherwise. // Assumes @param events is not empty. Aborts otherwise. @@ -1922,7 +1789,6 @@ class LeafSystem : public System { const Context& context, const EventCollection>& events) const final; - // Calls DoCalcDiscreteVariableUpdates (deprecated 2024-02-01). // Assumes @p events is an instance of LeafEventCollection, throws // std::bad_cast otherwise. // Assumes @p events is not empty. Aborts otherwise. @@ -1938,7 +1804,6 @@ class LeafSystem : public System { const EventCollection>& events, DiscreteValues* discrete_state, Context* context) const final; - // Calls DoCalcUnrestrictedUpdate (deprecated 2024-02-01). // Assumes @p events is an instance of LeafEventCollection, throws // std::bad_cast otherwise. // Assumes @p events is not empty. Aborts otherwise. diff --git a/systems/framework/output_port.h b/systems/framework/output_port.h index 7a6b4aa756b5..d150968d2f22 100644 --- a/systems/framework/output_port.h +++ b/systems/framework/output_port.h @@ -11,7 +11,6 @@ #include "drake/common/autodiff.h" #include "drake/common/default_scalars.h" #include "drake/common/drake_assert.h" -#include "drake/common/drake_deprecated.h" #include "drake/common/nice_type_name.h" #include "drake/common/type_safe_index.h" #include "drake/common/value.h" diff --git a/systems/framework/subvector.h b/systems/framework/subvector.h index 374aa0a6aff7..9f0c0e7d5410 100644 --- a/systems/framework/subvector.h +++ b/systems/framework/subvector.h @@ -6,7 +6,6 @@ #include "drake/common/default_scalars.h" #include "drake/common/drake_copyable.h" -#include "drake/common/drake_deprecated.h" #include "drake/common/drake_throw.h" #include "drake/systems/framework/vector_base.h" diff --git a/systems/framework/system.cc b/systems/framework/system.cc index d5f2e7762b1b..5ec67efc46cc 100644 --- a/systems/framework/system.cc +++ b/systems/framework/system.cc @@ -6,7 +6,6 @@ #include -#include "drake/common/drake_deprecated.h" #include "drake/common/unused.h" #include "drake/systems/framework/system_visitor.h" diff --git a/systems/framework/system.h b/systems/framework/system.h index 3f6d43ee2efe..522581ca523d 100644 --- a/systems/framework/system.h +++ b/systems/framework/system.h @@ -263,9 +263,7 @@ class System : public SystemBase { force-triggered event. @note There will always be at least one force-triggered event, though with no - associated handler. By default that will do nothing when triggered, but that - behavior can be changed by overriding the dispatcher DoPublish() - (not recommended). + associated handler (so will do nothing when triggered). The Simulator can be configured to call this in Simulator::Initialize() and at the start of each continuous integration step. See the Simulator API for more @@ -1494,19 +1492,15 @@ class System : public SystemBase { Drake's LeafSystem and Diagram (plus a few unit tests) and those implementations must be `final`. - For a LeafSystem, these functions need to call the appropriate LeafSystem::DoX - event dispatcher. E.g. LeafSystem::DispatchPublishHandler() calls - LeafSystem::DoPublish(). User supplied custom event callbacks embedded in each - individual event need to be invoked in the LeafSystem::DoX handlers if - desired. For a LeafSystem, the pseudo code of the complete default publish - event handler dispatching is roughly: + For a LeafSystem, these functions need to call each event's handler callback, + For a LeafSystem, the pseudo code of the complete default publish event + handler dispatching is roughly:
     leaf_sys.Publish(context, event_collection)
     -> leaf_sys.DispatchPublishHandler(context, event_collection)
-       -> leaf_sys.DoPublish(context, event_collection.get_events())
-          -> for (event : event_collection_events):
-               if (event.has_handler)
-                 event.handler(context)
+        for (event : event_collection_events):
+          if (event.has_handler)
+            event.handler(context)
   
Discrete update events and unrestricted update events are dispatched similarly for a LeafSystem. EventStatus is propagated upwards from the diff --git a/systems/framework/test/leaf_context_test.cc b/systems/framework/test/leaf_context_test.cc index 59930bc7b11e..db7af62376dd 100644 --- a/systems/framework/test/leaf_context_test.cc +++ b/systems/framework/test/leaf_context_test.cc @@ -931,18 +931,6 @@ TEST_F(LeafContextTest, PerturbTime) { EXPECT_FALSE(context_.get_true_time()); } -// Check that the hidden mutable "utility flag" in the Context can be set -// even in a const Context. -TEST_F(LeafContextTest, UtilityFlag) { - auto set_flag = [](const Context& context) { - context.set_use_default_implementation(true); - }; - - EXPECT_FALSE(context_.get_use_default_implementation()); - set_flag(context_); - EXPECT_TRUE(context_.get_use_default_implementation()); -} - } // namespace } // namespace systems } // namespace drake diff --git a/systems/framework/test/leaf_system_test.cc b/systems/framework/test/leaf_system_test.cc index 684914a2467d..343d4cc3b116 100644 --- a/systems/framework/test/leaf_system_test.cc +++ b/systems/framework/test/leaf_system_test.cc @@ -35,90 +35,6 @@ namespace drake { namespace systems { namespace { -// A shell System to test the event dispatchers are sent at least one event upon -// a forced call. -class ForcedDispatchOverrideSystem : public LeafSystem { - public: - bool got_publish_event() const { return got_publish_event_; } - bool got_discrete_update_event() const { - return got_discrete_update_event_; - } - bool got_unrestricted_update_event() const { - return got_unrestricted_update_event_; - } - TriggerType get_publish_event_trigger_type() const { - return publish_event_trigger_type_; - } - TriggerType get_discrete_update_event_trigger_type() const { - return discrete_update_event_trigger_type_; - } - TriggerType get_unrestricted_update_event_trigger_type() const { - return unrestricted_update_event_trigger_type_; - } - - private: - void DoPublish( - const Context&, - const std::vector*>& events) const final { - got_publish_event_ = (events.size() == 1); - if (got_publish_event_) - publish_event_trigger_type_ = events.front()->get_trigger_type(); - } - - void DoCalcDiscreteVariableUpdates( - const Context&, - const std::vector*>& events, - DiscreteValues*) const final { - got_discrete_update_event_ = (events.size() == 1); - if (got_discrete_update_event_) - discrete_update_event_trigger_type_ = events.front()->get_trigger_type(); - } - - void DoCalcUnrestrictedUpdate( - const Context&, - const std::vector*>& events, - State*) const final { - got_unrestricted_update_event_ = (events.size() == 1); - if (got_unrestricted_update_event_) { - unrestricted_update_event_trigger_type_ = - events.front()->get_trigger_type(); - } - } - - // Variables used to determine whether the handlers have been called with - // forced update events. Note: updating method variables in event handlers - // is an anti-pattern, but we do it here to simplify test code. - mutable bool got_publish_event_{false}; - mutable bool got_discrete_update_event_{false}; - mutable bool got_unrestricted_update_event_{false}; - mutable TriggerType publish_event_trigger_type_{TriggerType::kUnknown}; - mutable TriggerType discrete_update_event_trigger_type_{ - TriggerType::kUnknown - }; - mutable TriggerType unrestricted_update_event_trigger_type_{ - TriggerType::kUnknown - }; -}; - -GTEST_TEST(ForcedDispatchOverrideSystemTest, Dispatchers) { - ForcedDispatchOverrideSystem system; - auto context = system.CreateDefaultContext(); - auto discrete_values = system.AllocateDiscreteVariables(); - EXPECT_EQ(discrete_values->get_system_id(), context->get_system_id()); - auto state = context->CloneState(); - system.ForcedPublish(*context); - system.CalcForcedDiscreteVariableUpdate(*context, discrete_values.get()); - system.CalcForcedUnrestrictedUpdate(*context, state.get()); - ASSERT_TRUE(system.got_publish_event()); - ASSERT_TRUE(system.got_discrete_update_event()); - ASSERT_TRUE(system.got_unrestricted_update_event()); - EXPECT_TRUE(system.get_publish_event_trigger_type() == TriggerType::kForced); - EXPECT_TRUE(system.get_discrete_update_event_trigger_type() == - TriggerType::kForced); - EXPECT_TRUE(system.get_unrestricted_update_event_trigger_type() == - TriggerType::kForced); -} - // A shell System to test the default implementations. template class TestSystem : public LeafSystem { @@ -2396,121 +2312,6 @@ GTEST_TEST(GraphvizTest, Split) { EXPECT_THAT(dot, ::testing::HasSubstr("(split)")); } -// This class serves as the mechanism by which we confirm that LeafSystem's -// implementation of DispatchPublishHandler() actually calls DoPublish() and, -// furthermore, the per-event dispatch implemented in DoPublish is completely -// replaced by an overridden implementation. -// -// The system has to be able to detect when its DoPublish() is called but also -// has to allow us to detect the difference between the built-in LeafSystem -// publish event dispatching and the overridden behavior. -// We do this in the following way: -// -// 1. We create a system that overrides DoPublish(). -// a. The system can be configured to run in one of two modes: -// i. Ignore publish events. -// ii. Use default publication dispatch. -// iii. In either mode, we increment a counter that will allow us to -// recognize that our DoPublish override got exercised. -// b. The system declares one force publish event. -// i. The force event allows us to test both APIs -// System::Publish(context) and System::Publish(context, events). As -// all other trigger types exercise the two apis, we'll ignore other -// trigger types. -// ii. The event handler increments a counter allowing us to recognize -// when the *event* has been handled. -// 2. We instantiate the system and evaluate the force events on it. -// i. In the "default" mode, we should see DoPublish() and the event -// handler invoked. This allows us to observe the "default" behavior and -// see that it changes. -// ii. In the "ignore events" mode, we expect DoPublish() to be called but -// not the event handler - we'll have completely supplanted the -// LeafSystem::DoPublish implementation). -class DoPublishOverrideSystem : public LeafSystem { - public: - /* Constructs the system to *default* event handling -- events will *not* - be ignored. */ - DoPublishOverrideSystem() : LeafSystem() { - DeclareForcedPublishEvent(&DoPublishOverrideSystem::HandleEvent); - } - - bool ignore_events() const { return ignore_events_; } - void set_ignore_events(bool ignore_events) { ignore_events_ = ignore_events; } - int do_publish_count() const { return do_publish_count_; } - int event_handle_count() const { return event_handle_count_; } - - EventStatus HandleEvent(const Context&) const { - ++event_handle_count_; - return EventStatus::Succeeded(); - } - - // We need public access to the event collection to call - // Publish(context, events). - const EventCollection>& - get_forced_publish_events_collection() const { - return get_forced_publish_events(); - } - - private: -#pragma GCC diagnostic push -#pragma GCC diagnostic ignored "-Wdeprecated-declarations" - void DoPublish( - const Context& context, - const std::vector*>& events) const override { - ++do_publish_count_; - if (!ignore_events_) - LeafSystem::DoPublish(context, events); - } -#pragma GCC diagnostic pop - - // If true, DoPublish ignores events, calls LeafSystem::DoPublish() if false. - bool ignore_events_{false}; - - // These mutable system members are an anti-pattern only acceptable as part of - // a unit test. - - // The number of times DoPublish() has been called on this instance. - mutable int do_publish_count_{0}; - - // The number of times the force publish event handler has been called on this - // instance. - mutable int event_handle_count_{0}; -}; - -GTEST_TEST(DoPublishOverrideTest, ConfirmOverride) { - DoPublishOverrideSystem system; - std::unique_ptr> context = system.CreateDefaultContext(); - const EventCollection>& events = - system.get_forced_publish_events_collection(); - - // First test default behaviors - DoPublish gets called and event handler - // get called. - ASSERT_FALSE(system.ignore_events()); - ASSERT_EQ(system.do_publish_count(), 0); - ASSERT_EQ(system.event_handle_count(), 0); - - system.ForcedPublish(*context); - EXPECT_EQ(system.do_publish_count(), 1); - EXPECT_EQ(system.event_handle_count(), 1); - EventStatus status = system.Publish(*context, events); - EXPECT_TRUE(status.succeeded()); - EXPECT_EQ(system.do_publish_count(), 2); - EXPECT_EQ(system.event_handle_count(), 2); - - // Now ignore default behaviors. This confirms *our* DoPublish completely - // supplants the default behavior. - system.set_ignore_events(true); - ASSERT_TRUE(system.ignore_events()); - - system.ForcedPublish(*context); - EXPECT_EQ(system.do_publish_count(), 3); - EXPECT_EQ(system.event_handle_count(), 2); - status = system.Publish(*context, events); - EXPECT_TRUE(status.succeeded()); - EXPECT_EQ(system.do_publish_count(), 4); - EXPECT_EQ(system.event_handle_count(), 2); -} - // The custom context type for the CustomContextSystem. template class CustomContext : public LeafContext {}; @@ -2900,10 +2701,7 @@ GTEST_TEST(InitializationTest, DefaultEventProcessing) { EXPECT_TRUE(context->get_abstract_state(0)); } -// Although many of the tests above validate behavior of events when the -// event dispatchers DoPublish() etc are overridden, the preferred method -// for users is to provide individual handler functions for each event. There -// is a set of sugar methods to facilitate that; this class uses them all. +// This class uses every one of the functions that declare events. class EventSugarTestSystem : public LeafSystem { public: explicit EventSugarTestSystem(EventStatus::Severity desired_status = diff --git a/systems/framework/test/system_test.cc b/systems/framework/test/system_test.cc index 15c310c59a88..1ee6ed63da6f 100644 --- a/systems/framework/test/system_test.cc +++ b/systems/framework/test/system_test.cc @@ -356,8 +356,8 @@ TEST_F(SystemTest, VelocityConfigurationDerivativeSizeMismatch) { std::runtime_error); } -// Tests that the default DoPublish is invoked when no other handler is -// registered in DoCalcNextUpdateTime. +// Tests that default publishing is invoked when no other handler is registered +// in DoCalcNextUpdateTime. TEST_F(SystemTest, DiscretePublish) { context_->SetTime(5.0); auto event_info = system_.AllocateCompositeEventCollection(); diff --git a/systems/framework/test/vector_system_test.cc b/systems/framework/test/vector_system_test.cc index bc1b5436fb53..0b883b5e54d5 100644 --- a/systems/framework/test/vector_system_test.cc +++ b/systems/framework/test/vector_system_test.cc @@ -401,16 +401,8 @@ TEST_F(VectorSystemTest, NoInputContinuousTimeSystemTest) { class NoInputNoOutputDiscreteTimeSystem : public VectorSystem { public: - explicit NoInputNoOutputDiscreteTimeSystem(bool use_deprecated) - : VectorSystem(0, 0) { - if (use_deprecated) { -#pragma GCC diagnostic push -#pragma GCC diagnostic ignored "-Wdeprecated-declarations" - this->DeclarePeriodicDiscreteUpdateNoHandler(1.0); -#pragma GCC diagnostic pop - } else { - this->DeclarePeriodicDiscreteUpdate(1.0, 0.0); - } + NoInputNoOutputDiscreteTimeSystem() : VectorSystem(0, 0) { + this->DeclarePeriodicDiscreteUpdate(1.0, 0.0); this->DeclareDiscreteState(1); } @@ -428,22 +420,7 @@ class NoInputNoOutputDiscreteTimeSystem : public VectorSystem { // Discrete updates still work when input size is zero. // No output ports are created when the output size is zero. TEST_F(VectorSystemTest, NoInputNoOutputDiscreteTimeSystemTest) { - NoInputNoOutputDiscreteTimeSystem dut(/* deprecated = */ false); - auto context = dut.CreateDefaultContext(); - context->get_mutable_discrete_state().get_mutable_vector().SetFromVector( - Vector1d::Constant(2.0)); - - auto discrete_updates = dut.AllocateDiscreteVariables(); - dut.CalcForcedDiscreteVariableUpdate(*context, discrete_updates.get()); - EXPECT_EQ(discrete_updates->get_vector(0)[0], 8.0); - - EXPECT_EQ(dut.num_output_ports(), 0); -} - -// Discrete updates still work when input size is zero. -// No output ports are created when the output size is zero. -TEST_F(VectorSystemTest, NoInputNoOutputDiscreteTimeSystemTestDeprecated) { - NoInputNoOutputDiscreteTimeSystem dut(/* deprecated = */ true); + NoInputNoOutputDiscreteTimeSystem dut; auto context = dut.CreateDefaultContext(); context->get_mutable_discrete_state().get_mutable_vector().SetFromVector( Vector1d::Constant(2.0)); diff --git a/systems/framework/vector_system.h b/systems/framework/vector_system.h index 2054e3e4f43c..3525bf3fcdab 100644 --- a/systems/framework/vector_system.h +++ b/systems/framework/vector_system.h @@ -281,13 +281,6 @@ class VectorSystem : public LeafSystem { DRAKE_THROW_UNLESS(derivatives->size() == 0); } - DRAKE_DEPRECATED("2024-02-01", - "Use DeclarePeriodicDiscreteUpdate() instead.") - void DeclarePeriodicDiscreteUpdateNoHandler(double period_sec, - double offset_sec = 0.0) { - this->DeclarePeriodicDiscreteUpdate(period_sec, offset_sec); - } - /// Declares a discrete update rate. You must override /// DoCalcVectorDiscreteVariableUpdates() to handle the update. void DeclarePeriodicDiscreteUpdate(double period_sec, double offset_sec) { @@ -295,12 +288,9 @@ class VectorSystem : public LeafSystem { period_sec, offset_sec, &VectorSystem::CalcDiscreteUpdate); } - /// Provides a convenience method for %VectorSystem subclasses. This - /// method performs the same logical operation as - /// System::DoCalcDiscreteVariableUpdates but provides VectorBlocks to - /// represent the input, discrete state, and discrete updates. Subclasses - /// should override this method, and not the base class method (which is - /// `final`). + /// Provides a convenience method for %VectorSystem subclasses. This + /// method serves as the callback for DeclarePeriodicDiscreteUpdate(), + /// immediately above. /// /// The @p state will be either empty or the discrete state, depending on /// whether discrete state was declared at context-creation time. diff --git a/systems/lcm/lcm_subscriber_system.h b/systems/lcm/lcm_subscriber_system.h index e20755b9ee39..5bd8c90105cc 100644 --- a/systems/lcm/lcm_subscriber_system.h +++ b/systems/lcm/lcm_subscriber_system.h @@ -7,7 +7,6 @@ #include #include "drake/common/drake_copyable.h" -#include "drake/common/drake_deprecated.h" #include "drake/common/drake_throw.h" #include "drake/lcm/drake_lcm_interface.h" #include "drake/systems/framework/basic_vector.h" diff --git a/tools/workspace/default.bzl b/tools/workspace/default.bzl index a9c959f23630..41c95fe7426c 100644 --- a/tools/workspace/default.bzl +++ b/tools/workspace/default.bzl @@ -24,7 +24,6 @@ load("//tools/workspace/dm_control_internal:repository.bzl", "dm_control_interna load("//tools/workspace/drake_models:repository.bzl", "drake_models_repository") # noqa load("//tools/workspace/drake_visualizer:repository.bzl", "drake_visualizer_repository") # noqa load("//tools/workspace/eigen:repository.bzl", "eigen_repository") -load("//tools/workspace/expat:repository.bzl", "expat_repository") load("//tools/workspace/fcl_internal:repository.bzl", "fcl_internal_repository") # noqa load("//tools/workspace/fmt:repository.bzl", "fmt_repository") load("//tools/workspace/gflags:repository.bzl", "gflags_repository") @@ -45,13 +44,10 @@ load("//tools/workspace/ipopt_internal_pkgconfig:repository.bzl", "ipopt_interna load("//tools/workspace/lapack:repository.bzl", "lapack_repository") load("//tools/workspace/lcm:repository.bzl", "lcm_repository") load("//tools/workspace/libblas:repository.bzl", "libblas_repository") -load("//tools/workspace/libjpeg:repository.bzl", "libjpeg_repository") load("//tools/workspace/libjpeg_turbo_internal:repository.bzl", "libjpeg_turbo_internal_repository") # noqa load("//tools/workspace/liblapack:repository.bzl", "liblapack_repository") load("//tools/workspace/libpfm:repository.bzl", "libpfm_repository") -load("//tools/workspace/libpng:repository.bzl", "libpng_repository") load("//tools/workspace/libpng_internal:repository.bzl", "libpng_internal_repository") # noqa -load("//tools/workspace/libtiff:repository.bzl", "libtiff_repository") load("//tools/workspace/libtiff_internal:repository.bzl", "libtiff_internal_repository") # noqa load("//tools/workspace/meshcat:repository.bzl", "meshcat_repository") load("//tools/workspace/mosek:repository.bzl", "mosek_repository") @@ -169,10 +165,6 @@ def add_default_repositories(excludes = [], mirrors = DEFAULT_MIRRORS): drake_visualizer_repository(name = "drake_visualizer", mirrors = mirrors) # noqa if "eigen" not in excludes: eigen_repository(name = "eigen") - if "expat" not in excludes: - # The @expat external is deprecated in Drake's WORKSPACE and will be - # removed on or after 2024-02-01. - expat_repository(name = "expat") if "fcl_internal" not in excludes: fcl_internal_repository(name = "fcl_internal", mirrors = mirrors) if "fmt" not in excludes: @@ -213,26 +205,14 @@ def add_default_repositories(excludes = [], mirrors = DEFAULT_MIRRORS): lcm_repository(name = "lcm", mirrors = mirrors) if "libblas" not in excludes: libblas_repository(name = "libblas") - if "libjpeg" not in excludes: - # The @libjpeg external is deprecated in Drake's WORKSPACE and will be - # removed on or after 2024-02-01. - libjpeg_repository(name = "libjpeg") if "libjpeg_turbo_internal" not in excludes: libjpeg_turbo_internal_repository(name = "libjpeg_turbo_internal", mirrors = mirrors) # noqa if "liblapack" not in excludes: liblapack_repository(name = "liblapack") if "libpfm" not in excludes: libpfm_repository(name = "libpfm") - if "libpng" not in excludes: - # The @libpng external is deprecated in Drake's WORKSPACE and will be - # removed on or after 2024-02-01. - libpng_repository(name = "libpng") if "libpng_internal" not in excludes: libpng_internal_repository(name = "libpng_internal", mirrors = mirrors) - if "libtiff" not in excludes: - # The @libtiff external is deprecated in Drake's WORKSPACE and will be - # removed on or after 2024-02-01. - libtiff_repository(name = "libtiff") if "libtiff_internal" not in excludes: libtiff_internal_repository(name = "libtiff_internal", mirrors = mirrors) # noqa if "meshcat" not in excludes: diff --git a/tools/workspace/expat/BUILD.bazel b/tools/workspace/expat/BUILD.bazel deleted file mode 100644 index b77b93ae0dbc..000000000000 --- a/tools/workspace/expat/BUILD.bazel +++ /dev/null @@ -1,6 +0,0 @@ -# This file exists to make our directory into a Bazel package, so that our -# neighboring *.bzl file can be loaded elsewhere. - -load("//tools/lint:lint.bzl", "add_lint_tests") - -add_lint_tests() diff --git a/tools/workspace/expat/repository.bzl b/tools/workspace/expat/repository.bzl deleted file mode 100644 index fff8372f9fa1..000000000000 --- a/tools/workspace/expat/repository.bzl +++ /dev/null @@ -1,85 +0,0 @@ -""" -Makes a system-installed Expat XML parser headers and library available to be -used as a C/C++ dependency. On Ubuntu, pkg-config is used to locate the Expat -headers and library. On macOS, no pkg-config expat.pc file is installed, but -the Expat headers are included in the macOS SDK and the library is always -located at /usr/lib. - -Example: - WORKSPACE: - load("@drake//tools/workspace/expat:repository.bzl", "expat_repository") # noqa - expat_repository(name = "foo") - - BUILD: - cc_library( - name = "foobar", - deps = ["@foo//:expat"], - srcs = ["bar.cc"], - ) - -Argument: - name: A unique name for this rule. -""" - -load("//tools/workspace:execute.bzl", "execute_or_fail") -load("//tools/skylark:pathutils.bzl", "join_paths") -load("//tools/workspace:pkg_config.bzl", "setup_pkg_config_repository") -load("//tools/workspace:os.bzl", "determine_os") - -def _impl(repository_ctx): - os_result = determine_os(repository_ctx) - if os_result.error != None: - fail(os_result.error) - - if os_result.is_macos: - result = execute_or_fail(repository_ctx, ["xcrun", "--show-sdk-path"]) - include = join_paths(result.stdout.strip(), "usr/include") - repository_ctx.symlink( - join_paths(include, "expat.h"), - "include/expat.h", - ) - repository_ctx.symlink( - join_paths(include, "expat_external.h"), - "include/expat_external.h", - ) - - file_content = """# DO NOT EDIT: generated by expat_repository() - -load("@drake//tools/skylark:cc.bzl", "cc_library") - -licenses(["notice"]) # MIT - -cc_library( - name = "expat", - hdrs = [ - "include/expat_external.h", - "include/expat.h", - ], - includes = ["include"], - linkopts = ["-lexpat"], - visibility = ["//visibility:public"], - deprecation = "The @expat external is deprecated in Drake's WORKSPACE and will be removed on or after 2024-02-01.", # noqa -) -""" - - repository_ctx.file( - "BUILD.bazel", - content = file_content, - executable = False, - ) - else: - error = setup_pkg_config_repository(repository_ctx).error - - if error != None: - fail(error) - -expat_repository = repository_rule( - # TODO(jamiesnape): Pass down licenses to setup_pkg_config_repository. - attrs = { - "modname": attr.string(default = "expat"), - "extra_deprecation": attr.string(default = "The @expat external is deprecated in Drake's WORKSPACE and will be removed on or after 2024-02-01."), # noqa - }, - local = True, - configure = True, - implementation = _impl, -) diff --git a/tools/workspace/libjpeg/BUILD.bazel b/tools/workspace/libjpeg/BUILD.bazel deleted file mode 100644 index b77b93ae0dbc..000000000000 --- a/tools/workspace/libjpeg/BUILD.bazel +++ /dev/null @@ -1,6 +0,0 @@ -# This file exists to make our directory into a Bazel package, so that our -# neighboring *.bzl file can be loaded elsewhere. - -load("//tools/lint:lint.bzl", "add_lint_tests") - -add_lint_tests() diff --git a/tools/workspace/libjpeg/package.BUILD.bazel b/tools/workspace/libjpeg/package.BUILD.bazel deleted file mode 100644 index 985ad56e6cab..000000000000 --- a/tools/workspace/libjpeg/package.BUILD.bazel +++ /dev/null @@ -1,19 +0,0 @@ -# -*- bazel -*- - -load("@drake//tools/skylark:cc.bzl", "cc_library") -load(":vars.bzl", "LIBDIR") - -licenses(["notice"]) # IJG - -cc_library( - name = "libjpeg", - hdrs = glob(["include/*.h"]), - includes = ["include"], - linkopts = [ - "-L" + LIBDIR, - "-Wl,-rpath," + LIBDIR, - "-ljpeg", - ], - visibility = ["//visibility:public"], - deprecation = "The @libjpeg external is deprecated in Drake's WORKSPACE and will be removed on or after 2024-02-01.", # noqa -) diff --git a/tools/workspace/libjpeg/repository.bzl b/tools/workspace/libjpeg/repository.bzl deleted file mode 100644 index 64b0f97b07ad..000000000000 --- a/tools/workspace/libjpeg/repository.bzl +++ /dev/null @@ -1,55 +0,0 @@ -load("//tools/workspace:os.bzl", "determine_os") - -def _impl(repository_ctx): - os_result = determine_os(repository_ctx) - - if os_result.error != None: - fail(os_result.error) - - noarch_hdrs = ["jerror.h", "jmorecfg.h", "jpegint.h", "jpeglib.h"] - - if os_result.is_macos: - libdir = "{}/opt/jpeg/lib".format(os_result.homebrew_prefix) - repository_ctx.symlink( - "{}/opt/jpeg/include".format(os_result.homebrew_prefix), - "include", - ) - elif os_result.is_manylinux or os_result.is_macos_wheel: - libdir = "/opt/drake-dependencies/lib" - for hdr in noarch_hdrs + ["jconfig.h"]: - repository_ctx.symlink( - "/opt/drake-dependencies/include/{}".format(hdr), - "include/{}".format(hdr), - ) - elif os_result.is_ubuntu: - libdir = "/usr/lib/x86_64-linux-gnu" - for hdr in noarch_hdrs: - repository_ctx.symlink( - "/usr/include/{}".format(hdr), - "include/{}".format(hdr), - ) - repository_ctx.symlink( - "/usr/include/x86_64-linux-gnu/jconfig.h", - "include/jconfig.h", - ) - else: - fail("Operating system is NOT supported {}".format(os_result)) - - # Declare the libdir. - repository_ctx.file( - "vars.bzl", - content = "LIBDIR = \"{}\"\n".format(libdir), - executable = False, - ) - - # Add the BUILD file. - repository_ctx.symlink( - Label("@drake//tools/workspace/libjpeg:package.BUILD.bazel"), - "BUILD.bazel", - ) - -libjpeg_repository = repository_rule( - local = True, - configure = True, - implementation = _impl, -) diff --git a/tools/workspace/libpng/BUILD.bazel b/tools/workspace/libpng/BUILD.bazel deleted file mode 100644 index b77b93ae0dbc..000000000000 --- a/tools/workspace/libpng/BUILD.bazel +++ /dev/null @@ -1,6 +0,0 @@ -# This file exists to make our directory into a Bazel package, so that our -# neighboring *.bzl file can be loaded elsewhere. - -load("//tools/lint:lint.bzl", "add_lint_tests") - -add_lint_tests() diff --git a/tools/workspace/libpng/repository.bzl b/tools/workspace/libpng/repository.bzl deleted file mode 100644 index ff8e2640e7e7..000000000000 --- a/tools/workspace/libpng/repository.bzl +++ /dev/null @@ -1,9 +0,0 @@ -load("//tools/workspace:pkg_config.bzl", "pkg_config_repository") - -def libpng_repository(name): - pkg_config_repository( - name = name, - licenses = ["notice"], # Libpng - modname = "libpng", - extra_deprecation = "The @libpng external is deprecated in Drake's WORKSPACE and will be removed on or after 2024-02-01.", # noqa - ) diff --git a/tools/workspace/libtiff/BUILD.bazel b/tools/workspace/libtiff/BUILD.bazel deleted file mode 100644 index b77b93ae0dbc..000000000000 --- a/tools/workspace/libtiff/BUILD.bazel +++ /dev/null @@ -1,6 +0,0 @@ -# This file exists to make our directory into a Bazel package, so that our -# neighboring *.bzl file can be loaded elsewhere. - -load("//tools/lint:lint.bzl", "add_lint_tests") - -add_lint_tests() diff --git a/tools/workspace/libtiff/repository.bzl b/tools/workspace/libtiff/repository.bzl deleted file mode 100644 index b39eccef8d5e..000000000000 --- a/tools/workspace/libtiff/repository.bzl +++ /dev/null @@ -1,9 +0,0 @@ -load("//tools/workspace:pkg_config.bzl", "pkg_config_repository") - -def libtiff_repository(name): - pkg_config_repository( - name = name, - licenses = ["notice"], # Libtiff - modname = "libtiff-4", - extra_deprecation = "The @libtiff external is deprecated in Drake's WORKSPACE and will be removed on or after 2024-02-01.", # noqa - ) diff --git a/visualization/visualization_config_functions.h b/visualization/visualization_config_functions.h index cbfb18285510..4032d5457d3d 100644 --- a/visualization/visualization_config_functions.h +++ b/visualization/visualization_config_functions.h @@ -4,7 +4,6 @@ #include #include -#include "drake/common/drake_deprecated.h" #include "drake/geometry/drake_visualizer_params.h" #include "drake/geometry/meshcat.h" #include "drake/geometry/meshcat_visualizer_params.h"