Skip to content

Commit

Permalink
Remove deprecated methods (2019-06) (RobotLocomotion#11534)
Browse files Browse the repository at this point in the history
(This does not remove the solver-related deprecations for 2019-06; that
work is under a separate commit.)
  • Loading branch information
jwnimmer-tri authored Jun 3, 2019
1 parent d4c3796 commit 0cbaf23
Show file tree
Hide file tree
Showing 52 changed files with 37 additions and 3,044 deletions.
19 changes: 13 additions & 6 deletions bindings/pydrake/common/module_py.cc
Original file line number Diff line number Diff line change
Expand Up @@ -104,12 +104,19 @@ PYBIND11_MODULE(_module_py, m) {
"is replaced by a character from the portable filename character set. "
"Any trailing / will be stripped from the output.",
doc.temp_directory.doc);
// Returns the fully-qualified path to the root of the `drake` source tree.
#pragma GCC diagnostic push
#pragma GCC diagnostic ignored "-Wdeprecated-declarations"
m.def("GetDrakePath", &GetDrakePath, "Get Drake path",
doc.GetDrakePath.doc_deprecated);
#pragma GCC diagnostic pop // pop -Wdeprecated-declarations
// The pydrake function named GetDrakePath is residue from when there used to
// be a C++ method named drake::GetDrakePath(). For backward compatibility,
// we'll keep the pydrake function name intact even though there's no
// matching C++ method anymore.
m.def("GetDrakePath",
[]() {
py::object result;
if (auto optional_result = MaybeGetDrakePath()) {
result = py::str(*optional_result);
}
return result;
},
doc.MaybeGetDrakePath.doc);
// These are meant to be called internally by pydrake; not by users.
m.def("set_assertion_failure_to_throw_exception",
&drake_set_assertion_failure_to_throw_exception,
Expand Down
26 changes: 1 addition & 25 deletions bindings/pydrake/lcm_py.cc
Original file line number Diff line number Diff line change
Expand Up @@ -89,31 +89,7 @@ PYBIND11_MODULE(lcm, m) {
// Unsubscribe is not supported by the mock.
DRAKE_DEMAND(subscription == nullptr);
},
py::arg("channel"), py::arg("handler"), cls_doc.Subscribe.doc)
.def("InduceSubscriberCallback",
[](Class* self, const std::string& channel, py::bytes buffer) {
WarnDeprecated("Use Publish + HandleSubscriptions instead.");
#pragma GCC diagnostic push
#pragma GCC diagnostic ignored "-Wdeprecated-declarations"
std::string str = buffer;
self->InduceSubscriberCallback(channel, str.data(), str.size());
#pragma GCC diagnostic pop
},
py::arg("channel"), py::arg("buffer"),
cls_doc.InduceSubscriberCallback.doc_deprecated)
.def("get_last_published_message",
[](const Class* self, const std::string& channel) {
WarnDeprecated("Use pydrake.lcm.Subscriber instead.");
#pragma GCC diagnostic push
#pragma GCC diagnostic ignored "-Wdeprecated-declarations"
const std::vector<uint8_t>& bytes =
self->get_last_published_message(channel);
return py::bytes(
reinterpret_cast<const char*>(bytes.data()), bytes.size());
#pragma GCC diagnostic pop
},
py::arg("channel"),
cls_doc.get_last_published_message.doc_deprecated);
py::arg("channel"), py::arg("handler"), cls_doc.Subscribe.doc);
}

ExecuteExtraPythonCode(m);
Expand Down
11 changes: 0 additions & 11 deletions bindings/pydrake/systems/framework_py_semantics.cc
Original file line number Diff line number Diff line change
Expand Up @@ -105,17 +105,6 @@ void DefineFrameworkPySemantics(py::module m) {
.def("get_mutable_value", &AbstractValues::get_mutable_value,
py::arg("index"), py_reference_internal,
doc.AbstractValues.get_mutable_value.doc)
.def("CopyFrom",
[](AbstractValues* self, const AbstractValues& other) {
WarnDeprecated(
"Use SetFrom instead of CopyFrom. "
"This method will be removed on 2019-06-01.");
#pragma GCC diagnostic push
#pragma GCC diagnostic ignored "-Wdeprecated-declarations"
self->CopyFrom(other);
#pragma GCC diagnostic pop
},
doc.AbstractValues.CopyFrom.doc_deprecated)
.def("SetFrom", &AbstractValues::SetFrom, doc.AbstractValues.SetFrom.doc);

{
Expand Down
10 changes: 0 additions & 10 deletions bindings/pydrake/systems/lcm_py.cc
Original file line number Diff line number Diff line change
Expand Up @@ -173,16 +173,6 @@ PYBIND11_MODULE(lcm, m) {
py::keep_alive<1, 3>(),
// Keep alive: `self` keeps `DrakeLcmInterface` alive.
py::keep_alive<1, 4>(), doc.LcmSubscriberSystem.ctor.doc)
.def("CopyLatestMessageInto",
[](Class* self, State<double>* state) {
WarnDeprecated(
"This unit-test-only method is being made non-public.");
#pragma GCC diagnostic push
#pragma GCC diagnostic ignored "-Wdeprecated-declarations"
self->CopyLatestMessageInto(state);
#pragma GCC diagnostic pop
},
py::arg("state"), cls_doc.CopyLatestMessageInto.doc_deprecated)
.def("WaitForMessage", &Class::WaitForMessage,
py::arg("old_message_count"), py::arg("message") = nullptr,
py::arg("timeout") = -1, cls_doc.WaitForMessage.doc);
Expand Down
2 changes: 0 additions & 2 deletions bindings/pydrake/systems/test/custom_test.py
Original file line number Diff line number Diff line change
Expand Up @@ -548,8 +548,6 @@ def __init__(self):
self.assertEqual(
values.get_mutable_value(0).get_value(), model_value.get_value())
values.SetFrom(values.Clone())
with catch_drake_warnings(expected_count=1):
values.CopyFrom(values.Clone())

# Check parameter accessors.
self.assertEqual(system.num_abstract_parameters(), 1)
Expand Down
15 changes: 0 additions & 15 deletions bindings/pydrake/test/lcm_test.py
Original file line number Diff line number Diff line change
Expand Up @@ -58,18 +58,3 @@ def test_subscriber(self):
self.assertEqual(dut.message.x, self.quat.x)
self.assertEqual(dut.message.y, self.quat.y)
self.assertEqual(dut.message.z, self.quat.z)

def test_mock_lcm_get_last_published_message_deprecated(self):
dut = DrakeMockLcm()
dut.Publish(channel="TEST_CHANNEL", buffer=self.quat.encode())
with catch_drake_warnings(expected_count=1):
raw = dut.get_last_published_message("TEST_CHANNEL")
self.assertEqual(raw, self.quat.encode())

def test_mock_lcm_induce_subscriber_callback_deprecated(self):
dut = DrakeMockLcm()
dut.Subscribe(channel="TEST_CHANNEL", handler=self._handler)
with catch_drake_warnings(expected_count=1):
dut.InduceSubscriberCallback(
channel="TEST_CHANNEL", buffer=self.quat.encode())
self.assertEqual(self.count, 1)
20 changes: 0 additions & 20 deletions common/drake_assert.h
Original file line number Diff line number Diff line change
Expand Up @@ -47,9 +47,6 @@
/// failure with a message showing at least the condition text, function name,
/// file, and line.
#define DRAKE_DEMAND(condition)
/// (Deprecated.) Aborts the program (via ::abort) with a message showing at
/// least the function name, file, and line.
#define DRAKE_ABORT()
/// Silences a "no return value" compiler warning by calling a function that
/// always raises an exception or aborts (i.e., a function marked noreturn).
/// Only use this macro at a point where (1) a point in the code is truly
Expand All @@ -62,9 +59,6 @@
/// to silence false positive warnings. When in doubt, throw an exception
/// manually instead of using this macro.
#define DRAKE_UNREACHABLE()
/// (Deprecated.) Aborts the program (via ::abort) with a message showing at
/// least the given message (macro argument), function name, file, and line.
#define DRAKE_ABORT_MSG(message)
#else // DRAKE_DOXYGEN_CXX

// Users should NOT set these; only this header should set them.
Expand All @@ -91,14 +85,6 @@ namespace detail {
// Abort the program with an error message.
__attribute__((noreturn)) /* gcc is ok with [[noreturn]]; clang is not. */
void Abort(const char* condition, const char* func, const char* file, int line);
__attribute__((noreturn))
__attribute__((deprecated(
"\nDRAKE DEPRECATED: DRAKE_ABORT() and DRAKE_ABORT_MSG() are deprecated; "
"use 'throw' instead; this macro will be removed on 2019-06-01.")))
inline void DeprecatedAbort(
const char* condition, const char* func, const char* file, int line) {
Abort(condition, func, file, line);
}
// Report an assertion failure; will either Abort(...) or throw.
__attribute__((noreturn)) /* gcc is ok with [[noreturn]]; clang is not. */
void AssertionFailed(
Expand All @@ -120,9 +106,6 @@ struct ConditionTraits {
} // namespace assert
} // namespace drake

#define DRAKE_ABORT() \
::drake::detail::DeprecatedAbort(nullptr, __func__, __FILE__, __LINE__)

#define DRAKE_UNREACHABLE() \
::drake::detail::Abort( \
"Unreachable code was reached?!", __func__, __FILE__, __LINE__)
Expand All @@ -138,9 +121,6 @@ struct ConditionTraits {
} \
} while (0)

#define DRAKE_ABORT_MSG(msg) \
::drake::detail::DeprecatedAbort(msg, __func__, __FILE__, __LINE__)

#ifdef DRAKE_ASSERT_IS_ARMED
// Assertions are enabled.
namespace drake {
Expand Down
15 changes: 2 additions & 13 deletions common/drake_path.cc
Original file line number Diff line number Diff line change
Expand Up @@ -7,14 +7,13 @@
// N.B. This code is unit tested in test/find_resource_test.cc.

namespace drake {
namespace {

optional<std::string> MaybeGetDrakePathImpl(bool should_throw) {
optional<std::string> MaybeGetDrakePath() {
// Find something that represents where Drake resources live. This will be
// "/path/to/drake/.drake-find_resource-sentinel" where "/path/to/" names the
// root of Drake's git source tree (or perhaps an installed version of same).
const auto& find_result = FindResource("drake/.drake-find_resource-sentinel");
if (find_result.get_error_message() && !should_throw) {
if (find_result.get_error_message()) {
return nullopt;
}
spruce::path sentinel_path = find_result.get_absolute_path_or_throw();
Expand All @@ -24,14 +23,4 @@ optional<std::string> MaybeGetDrakePathImpl(bool should_throw) {
return sentinel_path.root();
}

} // namespace

optional<std::string> MaybeGetDrakePath() {
return MaybeGetDrakePathImpl(false);
}

std::string GetDrakePath() {
return *MaybeGetDrakePathImpl(true);
}

} // namespace drake
4 changes: 0 additions & 4 deletions common/drake_path.h
Original file line number Diff line number Diff line change
Expand Up @@ -7,10 +7,6 @@

namespace drake {

/// Returns the fully-qualified path to the root of the `drake` source tree.
DRAKE_DEPRECATED("2019-06-01", "Please use drake::FindResource() instead.")
std::string GetDrakePath();

/// (Advanced) Returns the fully-qualified path to the first folder containing
/// Drake resources as located by FindResource, or nullopt if none is found.
/// For example `${result}/examples/pendulum/Pendulum.urdf` would be the path
Expand Down
21 changes: 0 additions & 21 deletions common/test/drake_assert_test.cc
Original file line number Diff line number Diff line change
Expand Up @@ -24,27 +24,6 @@ GTEST_TEST(DrakeAssertTest, MatchingConfigTest) {
#endif
}

GTEST_TEST(DrakeAssertDeathTest, AbortTest) {
::testing::FLAGS_gtest_death_test_style = "threadsafe";
#pragma GCC diagnostic push
#pragma GCC diagnostic ignored "-Wdeprecated-declarations"
ASSERT_DEATH(
{ DRAKE_ABORT(); },
"abort: Failure at .*drake_assert_test.cc:.. in TestBody");
#pragma GCC diagnostic pop
}

GTEST_TEST(DrakeAssertDeathTest, AbortMsgTest) {
::testing::FLAGS_gtest_death_test_style = "threadsafe";
#pragma GCC diagnostic push
#pragma GCC diagnostic ignored "-Wdeprecated-declarations"
ASSERT_DEATH(
{ DRAKE_ABORT_MSG("stuff"); },
"abort: Failure at .*drake_assert_test.cc:.. in TestBody..: "
"condition 'stuff' failed");
#pragma GCC diagnostic pop
}

GTEST_TEST(DrakeAssertDeathTest, DemandTest) {
::testing::FLAGS_gtest_death_test_style = "threadsafe";
ASSERT_DEATH(
Expand Down
2 changes: 1 addition & 1 deletion doc/bazel.rst
Original file line number Diff line number Diff line change
Expand Up @@ -265,7 +265,7 @@ See https://docs.bazel.build/versions/master/user-manual.html#bazelrc.
Drake offers two flavors of SNOPT bindings for the MathematicalProgram:

- The ``--config snopt_f2c`` option selects the legacy bindings that use the
f2c compiler; these bindings will be removed on 2019-06-01.
f2c compiler; these bindings will be removed on 2019-07-01.
- The ``--config snopt_fortran`` option selects the bindings that use the
gfortran compiler; these bindings will be supported for the foreseeable
future.
Expand Down
Loading

0 comments on commit 0cbaf23

Please sign in to comment.