Skip to content

Commit

Permalink
Remove various deprecated code (RobotLocomotion#10051)
Browse files Browse the repository at this point in the history
  • Loading branch information
jwnimmer-tri authored Nov 26, 2018
1 parent bdcb093 commit efc2029
Show file tree
Hide file tree
Showing 38 changed files with 35 additions and 1,011 deletions.
2 changes: 1 addition & 1 deletion bindings/pydrake/lcm_py.cc
Original file line number Diff line number Diff line change
Expand Up @@ -67,7 +67,7 @@ PYBIND11_MODULE(lcm, m) {
},
py::arg("channel"), py::arg("handler"),
doc.DrakeMockLcm.Subscribe. // BR
doc_2args_conststdstring_drakelcmDrakeLcmInterfaceHandlerFunction)
doc)
.def("InduceSubscriberCallback",
[](Class* self, const std::string& channel, py::bytes buffer) {
std::string str = buffer;
Expand Down
14 changes: 0 additions & 14 deletions bindings/pydrake/systems/framework_py_semantics.cc
Original file line number Diff line number Diff line change
Expand Up @@ -272,20 +272,6 @@ void DefineFrameworkPySemantics(py::module m) {
.def("get_index", &InputPort<T>::get_index,
doc.InputPortBase.get_index.doc);

// TODO(eric.cousineau): Make these deprecated module attributes so that
// they present deprecation messages.
// N.B. While this is called over again for each `T`, it is idempotent
// (no averse side-effects).
m.attr("InputPortDescriptor") = m.attr("InputPort");
m.attr("InputPortDescriptor_") = m.attr("InputPort_");
#pragma GCC diagnostic push
#pragma GCC diagnostic ignored "-Wdeprecated-declarations"
// Use deprecated alias directly here, so that it's easy to know when to
// remove it from the Python code.
static_assert(std::is_same<InputPortDescriptor<T>, InputPort<T>>::value,
"Remove Python aliases once this causes a compilation error");
#pragma GCC diagnostic pop // pop -Wdeprecated-declarations

// Parameters.
auto parameters = DefineTemplateClassWithDefault<Parameters<T>>(
m, "Parameters", GetPyParam<T>(), doc.Parameters.doc);
Expand Down
11 changes: 1 addition & 10 deletions bindings/pydrake/systems/framework_py_systems.cc
Original file line number Diff line number Diff line change
Expand Up @@ -301,16 +301,7 @@ struct Impl {
.def("AllocateOutput",
overload_cast_explicit<unique_ptr<SystemOutput<T>>>(
&System<T>::AllocateOutput),
doc.System.AllocateOutput.doc_0args)
// TODO(sherm1) Deprecate this next signature (context unused).
.def("AllocateOutput",
[](const System<T>* self, const Context<T>&) {
WarnDeprecated(
"`System.AllocateOutput(self, Context)` is deprecated. "
"Please use `System.AllocateOutput(self)` instead.");
return self->AllocateOutput();
},
py::arg("context"), doc.System.AllocateOutput.doc_1args)
doc.System.AllocateOutput.doc)
.def("EvalVectorInput",
[](const System<T>* self, const Context<T>& arg1, int arg2) {
return self->EvalVectorInput(arg1, arg2);
Expand Down
9 changes: 0 additions & 9 deletions bindings/pydrake/systems/test/general_test.py
Original file line number Diff line number Diff line change
Expand Up @@ -93,11 +93,6 @@ def test_system_base_api(self):
self.assertEqual(system.get_num_output_ports(), 1)
self.assertEqual(system.GetInputPort("u1").get_index(), 1)
self.assertEqual(system.GetOutputPort("sum").get_index(), 0)
# Test deprecated methods.
context = system.CreateDefaultContext()
with warnings.catch_warnings(record=True) as w:
c = system.AllocateOutput(context)
self.assertEqual(len(w), 1)
# TODO(eric.cousineau): Consolidate the main API tests for `System`
# to this test point.

Expand Down Expand Up @@ -166,10 +161,6 @@ def test_instantiations(self):
self._check_instantiations(BasicVector_)
self._check_instantiations(Supervector_)
self._check_instantiations(Subvector_)
# Deprecated aliases.
# TODO(eric.cousineau): Make this raise a deprecation warning.
self._check_instantiations(mut.InputPortDescriptor_)
self.assertEqual(mut.InputPortDescriptor, mut.InputPort)

def test_scalar_type_conversion(self):
for T in [float, AutoDiffXd, Expression]:
Expand Down
21 changes: 0 additions & 21 deletions common/BUILD.bazel
Original file line number Diff line number Diff line change
Expand Up @@ -37,7 +37,6 @@ drake_cc_package_library(
":is_cloneable",
":is_less_than_comparable",
":nice_type_name",
":number_traits",
":pointer_cast",
":polynomial",
":reset_after_move",
Expand Down Expand Up @@ -96,7 +95,6 @@ drake_cc_library(
name = "drake_bool",
hdrs = [
"drake_bool.h",
"drake_bool_deprecated.h",
],
deps = [
":autodiff",
Expand All @@ -110,11 +108,6 @@ drake_cc_library(
hdrs = ["dummy_value.h"],
)

drake_cc_library(
name = "number_traits",
hdrs = ["number_traits.h"],
)

# Drake's specific ScalarType-providing libraries.
drake_cc_library(
name = "double",
Expand Down Expand Up @@ -220,7 +213,6 @@ drake_cc_library(
":essential",
":extract_double",
":hash",
":number_traits",
":polynomial",
"//math:matrix_util",
],
Expand Down Expand Up @@ -567,19 +559,6 @@ drake_cc_googletest(
],
)

drake_cc_googletest(
name = "drake_bool_deprecated_test",
copts = [
# This test for deprecated functions; so we don't want this warning.
"-Wno-deprecated-declarations",
],
deps = [
":drake_bool",
":symbolic",
"//common/test_utilities:symbolic_test_util",
],
)

drake_cc_googletest(
name = "reset_after_move_test",
deps = [
Expand Down
6 changes: 0 additions & 6 deletions common/drake_bool.h
Original file line number Diff line number Diff line change
Expand Up @@ -94,9 +94,3 @@ boolean<typename Derived::Scalar> none_of(
return none(m.unaryExpr(pred));
}
} // namespace drake

// Include our older functions for backwards compatibility.
// TODO(jwnimmer-tri) Delete drake_bool_deprecated.h on or about 2018-12-01.
#define DRAKE_BOOL_DEPRECATED_OK_TO_INCLUDE 1
#include "drake/common/drake_bool_deprecated.h"
#undef DRAKE_BOOL_DEPRECATED_OK_TO_INCLUDE
228 changes: 0 additions & 228 deletions common/drake_bool_deprecated.h

This file was deleted.

15 changes: 0 additions & 15 deletions common/number_traits.h

This file was deleted.

Loading

0 comments on commit efc2029

Please sign in to comment.