Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Remove deprecated code 2024-02 #20846

Merged
merged 1 commit into from
Feb 4, 2024
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
1 change: 0 additions & 1 deletion bindings/pydrake/multibody/BUILD.bazel
Original file line number Diff line number Diff line change
Expand Up @@ -477,7 +477,6 @@ drake_py_unittest(
":benchmarks_py",
":inverse_kinematics_py",
":parsing_py",
"//bindings/pydrake/common/test_utilities",
"//bindings/pydrake/planning",
],
)
Expand Down
177 changes: 0 additions & 177 deletions bindings/pydrake/multibody/inverse_kinematics_py.cc
Original file line number Diff line number Diff line change
Expand Up @@ -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"
Expand Down Expand Up @@ -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;
Expand Down Expand Up @@ -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<Class>;
py::class_<Class, Constraint, Ptr> 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<double>* const plant,
double minimum_distance,
systems::Context<double>* plant_context,
solvers::MinimumValuePenaltyFunction penalty_function,
double influence_distance_offset) {
return std::make_unique<Class>(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<AutoDiffXd>* const plant,
double minimum_distance,
systems::Context<AutoDiffXd>* plant_context,
solvers::MinimumValuePenaltyFunction penalty_function,
double influence_distance_offset) {
return std::make_unique<Class>(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<MinimumDistanceConstraint>(
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<MinimumDistanceConstraint>(
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<double>* plant,
double minimum_distance_lower, double minimum_distance_upper,
systems::Context<double>* plant_context,
PyPenaltyFunction penalty_function, double influence_distance) {
return std::make_unique<MinimumDistanceConstraint>(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<AutoDiffXd>* plant,
double minimum_distance_lower, double minimum_distance_upper,
systems::Context<AutoDiffXd>* plant_context,
PyPenaltyFunction penalty_function, double influence_distance) {
return std::make_unique<MinimumDistanceConstraint>(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;
Expand Down
39 changes: 1 addition & 38 deletions bindings/pydrake/multibody/plant_py.cc
Original file line number Diff line number Diff line change
Expand Up @@ -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<T>* self,
Context<T>* context) -> Eigen::Ref<VectorX<T>> {
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<T>* self,
Context<T>* context) -> Eigen::Ref<VectorX<T>> {
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<T>* self,
Context<T>* context) -> Eigen::Ref<VectorX<T>> {
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<T>* self, const Context<T>& context)
Expand Down
Loading