Skip to content

Commit

Permalink
lcm: Deprecate many APIs (RobotLocomotion#11166)
Browse files Browse the repository at this point in the history
  • Loading branch information
jwnimmer-tri authored Apr 10, 2019
1 parent 026f1ee commit ef3464b
Show file tree
Hide file tree
Showing 15 changed files with 129 additions and 19 deletions.
2 changes: 2 additions & 0 deletions bindings/pydrake/BUILD.bazel
Original file line number Diff line number Diff line change
Expand Up @@ -157,6 +157,7 @@ drake_pybind_library(
name = "lcm_py",
cc_deps = [
"//bindings/pydrake:documentation_pybind",
"//bindings/pydrake/common:deprecation_pybind",
"//bindings/pydrake/common:drake_optional_pybind",
],
cc_srcs = ["lcm_py.cc"],
Expand Down Expand Up @@ -379,6 +380,7 @@ drake_py_unittest(
name = "lcm_test",
deps = [
":lcm_py",
"//bindings/pydrake/common/test_utilities",
"@lcmtypes_robotlocomotion//:lcmtypes_robotlocomotion_py",
],
)
Expand Down
38 changes: 31 additions & 7 deletions bindings/pydrake/lcm_py.cc
Original file line number Diff line number Diff line change
Expand Up @@ -4,6 +4,7 @@
#include "pybind11/pybind11.h"
#include "pybind11/stl.h"

#include "drake/bindings/pydrake/common/deprecation_pybind.h"
#include "drake/bindings/pydrake/common/drake_optional_pybind.h"
#include "drake/bindings/pydrake/documentation_pybind.h"
#include "drake/bindings/pydrake/pydrake_pybind.h"
Expand Down Expand Up @@ -50,10 +51,26 @@ PYBIND11_MODULE(lcm, m) {
.def(py::init<>(), doc.DrakeLcm.ctor.doc_0args)
.def(py::init<std::string>(), py::arg("lcm_url"),
doc.DrakeLcm.ctor.doc_1args)
.def("StartReceiveThread", &Class::StartReceiveThread,
doc.DrakeLcm.StartReceiveThread.doc)
.def("StopReceiveThread", &Class::StopReceiveThread,
doc.DrakeLcm.StopReceiveThread.doc);
.def("StartReceiveThread",
[](DrakeLcm* self) {
WarnDeprecated(
"Call DrakeLcm.HandleSubscriptions periodically instead.");
#pragma GCC diagnostic push
#pragma GCC diagnostic ignored "-Wdeprecated-declarations"
self->StartReceiveThread();
#pragma GCC diagnostic pop
},
doc.DrakeLcm.StartReceiveThread.doc_deprecated)
.def("StopReceiveThread",
[](DrakeLcm* self) {
WarnDeprecated(
"Call DrakeLcm.HandleSubscriptions periodically instead.");
#pragma GCC diagnostic push
#pragma GCC diagnostic ignored "-Wdeprecated-declarations"
self->StopReceiveThread();
#pragma GCC diagnostic pop
},
doc.DrakeLcm.StopReceiveThread.doc_deprecated);
// TODO(eric.cousineau): Add remaining methods.
}

Expand All @@ -76,21 +93,28 @@ PYBIND11_MODULE(lcm, m) {
doc.DrakeMockLcm.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"),
doc.DrakeMockLcm.InduceSubscriberCallback.doc)
doc.DrakeMockLcm.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"),
doc.DrakeMockLcm.get_last_published_message.doc);
// TODO(eric.cousineau): Add remaining methods.
doc.DrakeMockLcm.get_last_published_message.doc_deprecated);
}

ExecuteExtraPythonCode(m);
Expand Down
1 change: 1 addition & 0 deletions bindings/pydrake/systems/BUILD.bazel
Original file line number Diff line number Diff line change
Expand Up @@ -248,6 +248,7 @@ drake_py_unittest(
":analysis_py",
":lcm_py",
":primitives_py",
"//bindings/pydrake/common/test_utilities:deprecation_py",
],
)

Expand Down
7 changes: 5 additions & 2 deletions bindings/pydrake/systems/test/lcm_test.py
Original file line number Diff line number Diff line change
Expand Up @@ -10,6 +10,7 @@

from robotlocomotion import header_t, quaternion_t

from pydrake.common.test_utilities.deprecation import catch_drake_warnings
from pydrake.lcm import DrakeLcm, DrakeMockLcm, Subscriber
from pydrake.systems.analysis import Simulator
from pydrake.systems.framework import (
Expand Down Expand Up @@ -117,7 +118,8 @@ def test_subscriber_wait_for_message(self):
# N.B. This will fail with `threading`. See below for using
# `multithreading`.
lcm = DrakeLcm("memq://")
lcm.StartReceiveThread()
with catch_drake_warnings(expected_count=1):
lcm.StartReceiveThread()
sub = mut.LcmSubscriberSystem.Make("TEST_LOOP", header_t, lcm)
value = AbstractValue.Make(header_t())
for i in range(3):
Expand All @@ -130,7 +132,8 @@ def test_subscriber_wait_for_message(self):
def test_subscriber_wait_for_message_with_timeout(self):
"""Confirms that the subscriber times out."""
lcm = DrakeLcm("memq://")
lcm.StartReceiveThread()
with catch_drake_warnings(expected_count=1):
lcm.StartReceiveThread()
sub = mut.LcmSubscriberSystem.Make("TEST_LOOP", header_t, lcm)
sub.WaitForMessage(0, timeout=0.02)
# This test fails if the test hangs.
Expand Down
21 changes: 13 additions & 8 deletions bindings/pydrake/test/lcm_test.py
Original file line number Diff line number Diff line change
Expand Up @@ -4,6 +4,8 @@

from robotlocomotion import quaternion_t

from pydrake.common.test_utilities.deprecation import catch_drake_warnings


class TestLcm(unittest.TestCase):
def setUp(self):
Expand All @@ -18,8 +20,9 @@ def test_lcm(self):
dut = DrakeLcm()
self.assertIsInstance(dut, DrakeLcmInterface)
# Quickly start and stop the receiving thread.
dut.StartReceiveThread()
dut.StopReceiveThread()
with catch_drake_warnings(expected_count=2):
dut.StartReceiveThread()
dut.StopReceiveThread()
# Test virtual function names.
dut.Publish
dut.HandleSubscriptions
Expand Down Expand Up @@ -56,15 +59,17 @@ def test_subscriber(self):
self.assertEqual(dut.message.y, self.quat.y)
self.assertEqual(dut.message.z, self.quat.z)

def test_mock_lcm_get_last_published_message(self):
def test_mock_lcm_get_last_published_message_deprecated(self):
dut = DrakeMockLcm()
dut.Publish(channel="TEST_CHANNEL", buffer=self.quat.encode())
raw = dut.get_last_published_message("TEST_CHANNEL")
self.assertEqual(raw, 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(self):
def test_mock_lcm_induce_subscriber_callback_deprecated(self):
dut = DrakeMockLcm()
dut.Subscribe(channel="TEST_CHANNEL", handler=self._handler)
dut.InduceSubscriberCallback(
channel="TEST_CHANNEL", buffer=self.quat.encode())
with catch_drake_warnings(expected_count=1):
dut.InduceSubscriberCallback(
channel="TEST_CHANNEL", buffer=self.quat.encode())
self.assertEqual(self.count, 1)
6 changes: 6 additions & 0 deletions lcm/BUILD.bazel
Original file line number Diff line number Diff line change
Expand Up @@ -143,6 +143,12 @@ drake_cc_googletest(

drake_cc_googletest(
name = "drake_mock_lcm_test",
copts = [
# TODO(jwnimmer-tri) Almost all of this unit test can be purged or
# simplified once the deprecated methods are purged. We'll defer that
# work until the slate is clean, so just suppress the warnings for now.
"-Wno-deprecated-declarations",
],
deps = [
":lcmt_drake_signal_utils",
":mock",
Expand Down
3 changes: 3 additions & 0 deletions lcm/drake_lcm.cc
Original file line number Diff line number Diff line change
Expand Up @@ -266,8 +266,11 @@ int DrakeLcm::HandleSubscriptions(int timeout_millis) {
}

DrakeLcm::~DrakeLcm() {
#pragma GCC diagnostic push
#pragma GCC diagnostic ignored "-Wdeprecated-declarations"
// Stop invoking the subscriptions, prior to destroying them.
StopReceiveThread();
#pragma GCC diagnostic pop

// Invalidate our DrakeSubscription objects.
for (const auto& weak_subscription : impl_->subscriptions_) {
Expand Down
23 changes: 23 additions & 0 deletions lcm/drake_lcm.h
Original file line number Diff line number Diff line change
Expand Up @@ -6,6 +6,7 @@
#include "lcm/lcm-cpp.hpp"

#include "drake/common/drake_copyable.h"
#include "drake/common/drake_deprecated.h"
#include "drake/lcm/drake_lcm_interface.h"

namespace drake {
Expand Down Expand Up @@ -44,6 +45,13 @@ class DrakeLcm : public DrakeLcmInterface {
*
* @pre StartReceiveThread() was not called.
*/
DRAKE_DEPRECATED("2019-08-01",
"Almost no Drake uses of LCM should require a background thread. "
"Please use DrakeLcmInterface::HandleSubscriptions() or "
"drake::systems::lcm::LcmInterfaceSystem instead. "
"In the unlikely event you really do need a thread, the implementation "
"of Start+Stop+IsRunning is simple; feel free to copy and adapt it, or "
"see https://github.com/RobotLocomotion/drake/pull/11166 for more ideas.")
void StartReceiveThread();

/**
Expand All @@ -55,6 +63,13 @@ class DrakeLcm : public DrakeLcmInterface {
*
* @pre StartReceiveThread() was called.
*/
DRAKE_DEPRECATED("2019-08-01",
"Almost no Drake uses of LCM should require a background thread. "
"Please use DrakeLcmInterface::HandleSubscriptions() or "
"drake::systems::lcm::LcmInterfaceSystem instead. "
"In the unlikely event you really do need a thread, the implementation "
"of Start+Stop+IsRunning is simple; feel free to copy and adapt it, or "
"see https://github.com/RobotLocomotion/drake/pull/11166 for more ideas.")
void StopReceiveThread();

/**
Expand All @@ -63,6 +78,13 @@ class DrakeLcm : public DrakeLcmInterface {
* @warning Almost no Drake uses of LCM should require a background thread.
* Please use HandleSubscriptions() or systems::LcmInterfaceSystem instead.
*/
DRAKE_DEPRECATED("2019-08-01",
"Almost no Drake uses of LCM should require a background thread. "
"Please use DrakeLcmInterface::HandleSubscriptions() or "
"drake::systems::lcm::LcmInterfaceSystem instead. "
"In the unlikely event you really do need a thread, the implementation "
"of Start+Stop+IsRunning is simple; feel free to copy and adapt it, or "
"see https://github.com/RobotLocomotion/drake/pull/11166 for more ideas.")
bool IsReceiveThreadRunning() const;

/**
Expand All @@ -75,6 +97,7 @@ class DrakeLcm : public DrakeLcmInterface {
/**
* Returns the LCM URL passed into the constructor; this can be empty.
*/
DRAKE_DEPRECATED("2019-06-01", "Call get_lcm_url instead.")
std::string get_requested_lcm_url() const;

/**
Expand Down
3 changes: 3 additions & 0 deletions lcm/drake_mock_lcm.cc
Original file line number Diff line number Diff line change
Expand Up @@ -28,7 +28,10 @@ void DrakeMockLcm::Publish(const std::string& channel, const void* data,
per_channel_data->handled = false;

if (enable_loop_back_) {
#pragma GCC diagnostic push
#pragma GCC diagnostic ignored "-Wdeprecated-declarations"
InduceSubscriberCallback(channel, data, data_size);
#pragma GCC diagnostic pop
}
}

Expand Down
13 changes: 13 additions & 0 deletions lcm/drake_mock_lcm.h
Original file line number Diff line number Diff line change
Expand Up @@ -6,6 +6,7 @@
#include <vector>

#include "drake/common/drake_copyable.h"
#include "drake/common/drake_deprecated.h"
#include "drake/common/drake_optional.h"
#include "drake/lcm/drake_lcm_interface.h"

Expand Down Expand Up @@ -34,6 +35,8 @@ class DrakeMockLcm : public DrakeLcmInterface {
* enabled, the only way to induce a call to a subscriber's callback function
* is through InduceSubscriberCallback().
*/
DRAKE_DEPRECATED("2019-06-01",
"Call HandleSubscriptions(0) to propagate messages instead.")
void EnableLoopBack() { enable_loop_back_ = true; }

/**
Expand All @@ -53,9 +56,13 @@ class DrakeMockLcm : public DrakeLcmInterface {
* channel.
*/
template<typename T>
DRAKE_DEPRECATED("2019-06-01", "Use a drake::lcm::Subscriber instead.")
T DecodeLastPublishedMessageAs(const std::string& channel) const {
#pragma GCC diagnostic push
#pragma GCC diagnostic ignored "-Wdeprecated-declarations"
const std::vector<uint8_t>& message_bytes =
get_last_published_message(channel);
#pragma GCC diagnostic pop

T transmitted_message{};
const int num_bytes = transmitted_message.decode(message_bytes.data(), 0,
Expand Down Expand Up @@ -83,6 +90,7 @@ class DrakeMockLcm : public DrakeLcmInterface {
*
* @pre A message was previously published on channel @p channel.
*/
DRAKE_DEPRECATED("2019-06-01", "Use a drake::lcm::Subscriber instead.")
const std::vector<uint8_t>& get_last_published_message(
const std::string& channel) const;

Expand All @@ -91,6 +99,10 @@ class DrakeMockLcm : public DrakeLcmInterface {
* Returns nullopt iff a message has never been published on this channel or
* the most recent Publish call had no time_sec.
*/
DRAKE_DEPRECATED("2019-06-01",
"There is no easy replacement. One option is to use a DrakeLcmLog "
"instead of a DrakeMockLcm; then, the logged lcm::LogEvent.timestamp "
"will show the publication time")
optional<double> get_last_publication_time(const std::string& channel) const;

/**
Expand All @@ -104,6 +116,7 @@ class DrakeMockLcm : public DrakeLcmInterface {
*
* @param[in] data_size The length of @data in bytes.
*/
DRAKE_DEPRECATED("2019-06-01", "Call drake::lcm::Publish() instead.")
void InduceSubscriberCallback(const std::string& channel, const void* data,
int data_size);

Expand Down
11 changes: 9 additions & 2 deletions lcm/lcm_receive_thread.h
Original file line number Diff line number Diff line change
Expand Up @@ -6,6 +6,7 @@
#include "lcm/lcm-cpp.hpp"

#include "drake/common/drake_copyable.h"
#include "drake/common/drake_deprecated.h"

namespace drake {
namespace lcm {
Expand All @@ -18,9 +19,15 @@ namespace lcm {
* Please use DrakeLcmInterface::HandleSubscriptions() or
* drake::systems::lcm::LcmInterfaceSystem instead.
*/
class LcmReceiveThread {
class DRAKE_DEPRECATED("2019-08-01",
"There is no replacement. This class is trivially simple; feel free to "
"copy and adapt it instead, if needed.")
LcmReceiveThread {
public:
DRAKE_NO_COPY_NO_MOVE_NO_ASSIGN(LcmReceiveThread);
#pragma GCC diagnostic push
#pragma GCC diagnostic ignored "-Wdeprecated-declarations"
DRAKE_NO_COPY_NO_MOVE_NO_ASSIGN(LcmReceiveThread)
#pragma GCC diagnostic pop

/**
* A constructor that instantiates the thread.
Expand Down
6 changes: 6 additions & 0 deletions lcm/test/drake_lcm_test.cc
Original file line number Diff line number Diff line change
Expand Up @@ -58,13 +58,19 @@ class DrakeLcmTest : public ::testing::Test {
};

TEST_F(DrakeLcmTest, DefaultUrlTest) {
#pragma GCC diagnostic push
#pragma GCC diagnostic ignored "-Wdeprecated-declarations"
EXPECT_EQ(dut_->get_requested_lcm_url(), "");
#pragma GCC diagnostic pop
EXPECT_GT(dut_->get_lcm_url().size(), 0);
}

TEST_F(DrakeLcmTest, CustomUrlTest) {
dut_ = std::make_unique<DrakeLcm>(kUdpmUrl);
#pragma GCC diagnostic push
#pragma GCC diagnostic ignored "-Wdeprecated-declarations"
EXPECT_EQ(dut_->get_requested_lcm_url(), kUdpmUrl);
#pragma GCC diagnostic pop
EXPECT_EQ(dut_->get_lcm_url(), kUdpmUrl);
}

Expand Down
8 changes: 8 additions & 0 deletions lcm/test/drake_lcm_thread_test.cc
Original file line number Diff line number Diff line change
Expand Up @@ -101,9 +101,14 @@ class DrakeLcmThreadTest : public ::testing::Test {
// Call publish() until the mailbox matches our expected message.
void LoopUntilDone(const MessageMailbox& mailbox,
const std::function<void(void)>& publish) {
// TODO(jwnimmer-tri) When DrakeLcm loses its Thread methods, just make a
// std::thread here instead.
#pragma GCC diagnostic push
#pragma GCC diagnostic ignored "-Wdeprecated-declarations"
EXPECT_FALSE(dut_.IsReceiveThreadRunning());
dut_.StartReceiveThread();
EXPECT_TRUE(dut_.IsReceiveThreadRunning());
#pragma GCC diagnostic pop

// Try until we're either done, or we timeout (5 seconds).
const std::chrono::milliseconds kDelay(50);
Expand All @@ -118,8 +123,11 @@ class DrakeLcmThreadTest : public ::testing::Test {
}
EXPECT_TRUE(message_was_received);

#pragma GCC diagnostic push
#pragma GCC diagnostic ignored "-Wdeprecated-declarations"
dut_.StopReceiveThread();
EXPECT_FALSE(dut_.IsReceiveThreadRunning());
#pragma GCC diagnostic pop
}

// The device under test.
Expand Down
Loading

0 comments on commit ef3464b

Please sign in to comment.