Skip to content

Commit

Permalink
Remove deprecated code 2021-01 (RobotLocomotion#14486)
Browse files Browse the repository at this point in the history
* Remove deprecated code 2021-01
  • Loading branch information
jwnimmer-tri authored Jan 4, 2021
1 parent 15a66d7 commit 2447c2f
Show file tree
Hide file tree
Showing 27 changed files with 8 additions and 668 deletions.
43 changes: 3 additions & 40 deletions bindings/pydrake/systems/framework_py_semantics.cc
Original file line number Diff line number Diff line change
Expand Up @@ -6,7 +6,6 @@

#include "drake/bindings/pydrake/common/cpp_template_pybind.h"
#include "drake/bindings/pydrake/common/default_scalars_pybind.h"
#include "drake/bindings/pydrake/common/deprecation_pybind.h"
#include "drake/bindings/pydrake/common/eigen_pybind.h"
#include "drake/bindings/pydrake/common/type_safe_index_pybind.h"
#include "drake/bindings/pydrake/common/wrap_pybind.h"
Expand Down Expand Up @@ -47,10 +46,6 @@ py::object DoEval(const SomeObject* self, const systems::Context<T>& context) {
}
} // namespace

const char* doc_fix_input_port_deprecation =
"Use input_port.FixValue() instead of context.FixInputPort(). This will be "
"removed from Drake on or after 2021-01-01.";

void DefineFrameworkPySemantics(py::module m) {
// NOLINTNEXTLINE(build/namespaces): Emulate placement in namespace.
using namespace drake::systems;
Expand Down Expand Up @@ -295,41 +290,9 @@ void DefineFrameworkPySemantics(py::module m) {
abstract_value.attr("set_value")(value);
},
py::arg("index"), py::arg("value"),
doc.Context.SetAbstractState.doc);
// NOTE: SetTimeStateAndParametersFrom is bound below in
// bind_context_methods_templated_on_a_secondary_scalar
#pragma GCC diagnostic push
#pragma GCC diagnostic ignored "-Wdeprecated-declarations"
context_cls
.def(
"FixInputPort",
[](Context<T>* self, int index, const BasicVector<T>& vec) {
WarnDeprecated(doc_fix_input_port_deprecation);
return &self->FixInputPort(index, vec);
},
py::arg("index"), py::arg("vec"), py_rvp::reference_internal,
doc.Context.FixInputPort.doc_deprecated_deprecated_2args_index_vec)
.def(
"FixInputPort",
[](Context<T>* self, int index, unique_ptr<AbstractValue> value) {
WarnDeprecated(doc_fix_input_port_deprecation);
return &self->FixInputPort(index, std::move(value));
},
py::arg("index"), py::arg("value"), py_rvp::reference_internal,
// Keep alive, ownership: `AbstractValue` keeps `self` alive.
py::keep_alive<3, 1>(), doc.ContextBase.FixInputPort.doc)
.def(
"FixInputPort",
[](Context<T>* self, int index,
const Eigen::Ref<const VectorX<T>>& data) {
WarnDeprecated(doc_fix_input_port_deprecation);
return &self->FixInputPort(index, data);
},
py::arg("index"), py::arg("data"), py_rvp::reference_internal,
doc.Context.FixInputPort
.doc_deprecated_deprecated_2args_index_data);
#pragma GCC diagnostic pop
context_cls
doc.Context.SetAbstractState.doc)
// NOTE: SetTimeStateAndParametersFrom is bound below in
// bind_context_methods_templated_on_a_secondary_scalar
.def("SetAccuracy", &Context<T>::SetAccuracy, py::arg("accuracy"),
doc.Context.SetAccuracy.doc)
// Bindings for the Context methods in the Doxygen group titled
Expand Down
18 changes: 0 additions & 18 deletions bindings/pydrake/systems/test/general_test.py
Original file line number Diff line number Diff line change
Expand Up @@ -818,24 +818,6 @@ def test_vector_input_port_fix(self, T):
# type-erased Value objects are incompatible.
input_port.FixValue(context, AbstractValue.Make("string"))

def test_context_fix_input_port(self):
# WARNING: This is not the recommend workflow; instead, use
# `InputPort.FixValue` instead. This is here just for testing /
# coverage purposes.
dt = 0.1 # Arbitrary.
system_vec = ZeroOrderHold(period_sec=dt, vector_size=1)
context_vec = system_vec.CreateDefaultContext()
with catch_drake_warnings(expected_count=2):
context_vec.FixInputPort(index=0, data=[0.])
context_vec.FixInputPort(index=0, vec=BasicVector([0.]))
# Test abstract.
model_value = AbstractValue.Make("Hello")
system_abstract = ZeroOrderHold(
period_sec=dt, abstract_model_value=model_value.Clone())
context_abstract = system_abstract.CreateDefaultContext()
with catch_drake_warnings(expected_count=1):
context_abstract.FixInputPort(index=0, value=model_value.Clone())

def test_event_status(self):
system = ZeroOrderHold(period_sec=0.1, vector_size=1)
# Existence check.
Expand Down
8 changes: 0 additions & 8 deletions geometry/proximity/BUILD.bazel
Original file line number Diff line number Diff line change
Expand Up @@ -14,7 +14,6 @@ drake_cc_package_library(
name = "proximity",
visibility = ["//visibility:public"],
deps = [
":bounding_volume_hierarchy",
":bvh",
":collision_filter_legacy",
":collisions_exist_callback",
Expand Down Expand Up @@ -53,12 +52,6 @@ drake_cc_package_library(
],
)

drake_cc_library(
name = "bounding_volume_hierarchy",
hdrs = ["bounding_volume_hierarchy.h"],
deps = [":bvh"],
)

drake_cc_library(
name = "bvh",
srcs = ["bvh.cc"],
Expand Down Expand Up @@ -562,7 +555,6 @@ drake_cc_library(
drake_cc_googletest(
name = "bvh_test",
deps = [
":bounding_volume_hierarchy",
":bvh",
":make_ellipsoid_mesh",
":make_sphere_mesh",
Expand Down
17 changes: 0 additions & 17 deletions geometry/proximity/bounding_volume_hierarchy.h

This file was deleted.

14 changes: 0 additions & 14 deletions geometry/proximity/test/bvh_test.cc
Original file line number Diff line number Diff line change
Expand Up @@ -3,7 +3,6 @@
#include <gtest/gtest.h>

#include "drake/common/test_utilities/eigen_matrix_compare.h"
#include "drake/geometry/proximity/bounding_volume_hierarchy.h"
#include "drake/geometry/proximity/make_ellipsoid_mesh.h"
#include "drake/geometry/proximity/make_sphere_mesh.h"
#include "drake/geometry/proximity/obb.h"
Expand Down Expand Up @@ -70,19 +69,6 @@ class BvhTester {
};

namespace {
#pragma GCC diagnostic push
#pragma GCC diagnostic ignored "-Wdeprecated-declarations"

// Since we are deprecating BoundingVolumeHierarchy by aliasing it as Bvh,
// here we test an instantiation of the alias. We should remove this test at
// the end of deprecation period.
GTEST_TEST(BoundingVolumeHierarchyTest, TestInstantiation) {
const SurfaceMesh<double> mesh =
MakeSphereSurfaceMesh<double>(Sphere(1.5), 3);
const BoundingVolumeHierarchy<SurfaceMesh<double>> bvh(mesh);
}

#pragma GCC diagnostic pop // pop "-Wdeprecated-declarations"

GTEST_TEST(BvNodeTest, TestEqualLeaf) {
// Bounding volume is not used in EqualLeaf. It is used in EqualTrees.
Expand Down
22 changes: 0 additions & 22 deletions math/BUILD.bazel
Original file line number Diff line number Diff line change
Expand Up @@ -24,7 +24,6 @@ drake_cc_package_library(
":discrete_lyapunov_equation",
":eigen_sparse_triplet",
":evenly_distributed_pts_on_sphere",
":expmap",
":geometric_transform",
":gradient",
":gray_code",
Expand Down Expand Up @@ -216,16 +215,6 @@ drake_cc_library(
deps = ["@eigen"],
)

drake_cc_library(
name = "expmap",
srcs = ["expmap.cc"],
hdrs = ["expmap.h"],
deps = [
":gradient",
"//common:essential",
],
)

drake_cc_library(
name = "gray_code",
srcs = ["gray_code.cc"],
Expand Down Expand Up @@ -377,17 +366,6 @@ drake_cc_googletest(
],
)

drake_cc_googletest(
name = "expmap_test",
copts = [
"-Wno-deprecated-declarations",
],
deps = [
":expmap",
"//common/test_utilities:eigen_matrix_compare",
],
)

drake_cc_googletest(
name = "eigen_sparse_triplet_test",
deps = [
Expand Down
4 changes: 0 additions & 4 deletions math/expmap.cc

This file was deleted.

Loading

0 comments on commit 2447c2f

Please sign in to comment.