Skip to content

Commit

Permalink
lcm: Remove deprecated methods (2019-08) (RobotLocomotion#11840)
Browse files Browse the repository at this point in the history
  • Loading branch information
jwnimmer-tri authored Aug 1, 2019
1 parent 594f186 commit e128284
Show file tree
Hide file tree
Showing 20 changed files with 24 additions and 1,226 deletions.
1 change: 0 additions & 1 deletion bindings/pydrake/BUILD.bazel
Original file line number Diff line number Diff line change
Expand Up @@ -425,7 +425,6 @@ drake_py_unittest(
name = "lcm_test",
deps = [
":lcm_py",
"//bindings/pydrake/common/test_utilities",
"@lcmtypes_robotlocomotion//:lcmtypes_robotlocomotion_py",
],
)
Expand Down
24 changes: 2 additions & 22 deletions bindings/pydrake/lcm_py.cc
Original file line number Diff line number Diff line change
Expand Up @@ -49,28 +49,8 @@ PYBIND11_MODULE(lcm, m) {
constexpr auto& cls_doc = doc.DrakeLcm;
py::class_<Class, DrakeLcmInterface>(m, "DrakeLcm", cls_doc.doc)
.def(py::init<>(), cls_doc.ctor.doc_0args)
.def(
py::init<std::string>(), py::arg("lcm_url"), cls_doc.ctor.doc_1args)
.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
},
cls_doc.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
},
cls_doc.StopReceiveThread.doc_deprecated);
.def(py::init<std::string>(), py::arg("lcm_url"),
cls_doc.ctor.doc_1args);
// TODO(eric.cousineau): Add remaining methods.
}

Expand Down
15 changes: 0 additions & 15 deletions bindings/pydrake/systems/_lcm_extra.py
Original file line number Diff line number Diff line change
Expand Up @@ -26,21 +26,6 @@ def Serialize(self, abstract_value):
return message.encode()


class PyUtimeMessageToSeconds(LcmMessageToTimeInterface):
"""Provides a Python implementation of `UtimeMessageToSeconds` for use
with `LcmDrivenLoop`.
"""
def __init__(self, lcm_type):
LcmMessageToTimeInterface.__init__(self)
self._lcm_type = lcm_type

def GetTimeInSeconds(self, abstract_value):
assert isinstance(abstract_value, AbstractValue)
message = abstract_value.get_value()
assert isinstance(message, self._lcm_type)
return message.utime / 1.0e6


@staticmethod
def _make_lcm_subscriber(channel, lcm_type, lcm, use_cpp_serializer=False):
"""Convenience to create an LCM subscriber system with a concrete type.
Expand Down
78 changes: 0 additions & 78 deletions bindings/pydrake/systems/lcm_py.cc
Original file line number Diff line number Diff line change
Expand Up @@ -10,7 +10,6 @@
#include "drake/lcm/drake_lcm.h"
#include "drake/lcm/drake_lcm_interface.h"
#include "drake/systems/lcm/connect_lcm_scope.h"
#include "drake/systems/lcm/lcm_driven_loop.h"
#include "drake/systems/lcm/lcm_publisher_system.h"
#include "drake/systems/lcm/lcm_subscriber_system.h"
#include "drake/systems/lcm/serializer.h"
Expand All @@ -21,14 +20,8 @@ namespace pydrake {
using lcm::DrakeLcm;
using lcm::DrakeLcmInterface;
using pysystems::pylcm::BindCppSerializers;
using systems::lcm::LcmMessageToTimeInterface;
using systems::lcm::SerializerInterface;

constexpr const char* const kLcmDrivenLoopDeprecationString =
"LcmDrivenLoop is deprecated with no direct replacement; see "
"https://github.com/RobotLocomotion/drake/pull/11281 for suggestions. "
"This class will be removed on 2019-08-01.";

namespace {

// pybind11 trampoline class to permit overriding virtual functions in
Expand Down Expand Up @@ -72,22 +65,6 @@ class PySerializerInterface : public py::wrapper<SerializerInterface> {
}
};

#pragma GCC diagnostic push
#pragma GCC diagnostic ignored "-Wdeprecated-declarations"
class PyLcmMessageToTimeInterface
: public py::wrapper<LcmMessageToTimeInterface> {
public:
using Base = py::wrapper<LcmMessageToTimeInterface>;

PyLcmMessageToTimeInterface() : Base() {}

double GetTimeInSeconds(const AbstractValue& abstract_value) const override {
PYBIND11_OVERLOAD_PURE(
double, LcmMessageToTimeInterface, GetTimeInSeconds, &abstract_value);
}
};
#pragma GCC diagnostic pop

} // namespace

PYBIND11_MODULE(lcm, m) {
Expand Down Expand Up @@ -135,20 +112,6 @@ PYBIND11_MODULE(lcm, m) {
py::arg("abstract_value"), cls_doc.Serialize.doc);
}

{
#pragma GCC diagnostic push
#pragma GCC diagnostic ignored "-Wdeprecated-declarations"
using Class = LcmMessageToTimeInterface;
py::class_<Class, PyLcmMessageToTimeInterface>(
m, "LcmMessageToTimeInterface")
.def(py::init([]() {
WarnDeprecated(kLcmDrivenLoopDeprecationString);
return std::make_unique<PyLcmMessageToTimeInterface>();
}),
doc.LcmMessageToTimeInterface.doc_deprecated);
#pragma GCC diagnostic pop
}

{
using Class = LcmPublisherSystem;
constexpr auto& cls_doc = doc.LcmPublisherSystem;
Expand Down Expand Up @@ -178,47 +141,6 @@ PYBIND11_MODULE(lcm, m) {
py::arg("timeout") = -1, cls_doc.WaitForMessage.doc);
}

{
#pragma GCC diagnostic push
#pragma GCC diagnostic ignored "-Wdeprecated-declarations"
using Class = LcmDrivenLoop;
py::class_<Class>(m, "LcmDrivenLoop")
.def(
py::init(
[](const System<double>& system,
const LcmSubscriberSystem& driving_subscriber,
std::unique_ptr<Context<double>> context, DrakeLcm* lcm,
std::unique_ptr<LcmMessageToTimeInterface> time_converter) {
WarnDeprecated(kLcmDrivenLoopDeprecationString);
return std::make_unique<LcmDrivenLoop>(system,
driving_subscriber, std::move(context), lcm,
std::move(time_converter));
}),
py::arg("system"), py::arg("driving_subscriber"),
py::arg("context"), py::arg("lcm"), py::arg("time_converter"),
// Keep alive, ownership: `Context` keeps `self` alive.
py::keep_alive<4, 1>(),
// Keep alive, reference: `self` keeps `DrakeLcm` alive.
py::keep_alive<1, 5>(),
// Keep alive, ownership: `time_converter` keeps `self` alive.
py::keep_alive<6, 1>(), doc.LcmDrivenLoop.ctor.doc_deprecated)
.def("WaitForMessage", &Class::WaitForMessage, py_reference_internal,
doc.LcmDrivenLoop.WaitForMessage.doc)
.def("RunToSecondsAssumingInitialized",
&Class::RunToSecondsAssumingInitialized,
py::arg("stop_time") = std::numeric_limits<double>::infinity(),
doc.LcmDrivenLoop.RunToSecondsAssumingInitialized.doc)
.def("set_publish_on_every_received_message",
&Class::set_publish_on_every_received_message,
doc.LcmDrivenLoop.set_publish_on_every_received_message.doc)
.def("get_mutable_context", &Class::get_mutable_context,
py_reference_internal, doc.LcmDrivenLoop.get_mutable_context.doc)
.def("get_message_to_time_converter",
&Class::get_message_to_time_converter, py_reference_internal,
doc.LcmDrivenLoop.get_message_to_time_converter.doc);
#pragma GCC diagnostic pop
}

m.def("ConnectLcmScope", &ConnectLcmScope, py::arg("src"), py::arg("channel"),
py::arg("builder"), py::arg("lcm") = nullptr, py::keep_alive<0, 2>(),
// See #11531 for why `py_reference` is needed.
Expand Down
105 changes: 10 additions & 95 deletions bindings/pydrake/systems/test/lcm_test.py
Original file line number Diff line number Diff line change
Expand Up @@ -113,30 +113,21 @@ def test_subscriber_cpp(self):
self.assert_lcm_equal(actual_message, model_message)

def test_subscriber_wait_for_message(self):
"""Ensures that `WaitForMessage` threading works in a Python workflow
that is not threaded."""
# N.B. This will fail with `threading`. See below for using
# `multithreading`.
"""Checks how `WaitForMessage` works without Python threads."""
lcm = DrakeLcm("memq://")
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):
for old_message_count in range(3):
message = header_t()
message.utime = i
message.utime = old_message_count + 1
lcm.Publish("TEST_LOOP", message.encode())
sub.WaitForMessage(i, value)
self.assertEqual(value.get_value().utime, i)

def test_subscriber_wait_for_message_with_timeout(self):
"""Confirms that the subscriber times out."""
lcm = DrakeLcm("memq://")
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.
for attempt in range(10):
new_count = sub.WaitForMessage(
old_message_count, value, timeout=0.02)
if new_count > old_message_count:
break
lcm.HandleSubscriptions(0)
self.assertEqual(value.get_value().utime, old_message_count + 1)

def _fix_and_publish(self, dut, value):
context = dut.CreateDefaultContext()
Expand Down Expand Up @@ -173,79 +164,3 @@ def test_connect_lcm_scope(self):
channel="TEST_CHANNEL",
builder=builder,
lcm=DrakeMockLcm())

def test_utime_to_seconds(self):
msg = header_t()
msg.utime = int(1e6)
with catch_drake_warnings(expected_count=1):
dut = mut.PyUtimeMessageToSeconds(header_t)
t_sec = dut.GetTimeInSeconds(AbstractValue.Make(msg))
self.assertEqual(t_sec, 1)

def test_lcm_driven_loop(self):
"""Duplicates the test logic in `lcm_driven_loop_test.cc`."""
lcm_url = "udpm://239.255.76.67:7669"
t_start = 3.
t_end = 10.

def publish_loop():
# Publishes a set of messages for the driven loop. This should be
# run from a separate process.
# N.B. Because of this, care should be taken not to share C++
# objects between process boundaries.
t = t_start
while t <= t_end:
message = header_t()
message.utime = int(1e6 * t)
lcm.Publish("TEST_LOOP", message.encode())
time.sleep(0.1)
t += 1

class DummySys(LeafSystem):
# Converts message to time in seconds.
def __init__(self):
LeafSystem.__init__(self)
self.DeclareAbstractInputPort(
"header_t", AbstractValue.Make(header_t))
self.DeclareVectorOutputPort(
BasicVector(1), self._calc_output)

def _calc_output(self, context, output):
message = self.EvalAbstractInput(context, 0).get_value()
y = output.get_mutable_value()
y[:] = message.utime / 1e6

# Construct diagram for LcmDrivenLoop.
lcm = DrakeLcm(lcm_url)
with catch_drake_warnings(expected_count=1):
utime = mut.PyUtimeMessageToSeconds(header_t)
sub = mut.LcmSubscriberSystem.Make("TEST_LOOP", header_t, lcm)
builder = DiagramBuilder()
builder.AddSystem(sub)
dummy = builder.AddSystem(DummySys())
builder.Connect(sub.get_output_port(0), dummy.get_input_port(0))
logger = LogOutput(dummy.get_output_port(0), builder)
logger.set_forced_publish_only()
diagram = builder.Build()
with catch_drake_warnings(expected_count=1):
dut = mut.LcmDrivenLoop(diagram, sub, None, lcm, utime)
dut.set_publish_on_every_received_message(True)

# N.B. Use `multiprocessing` instead of `threading` so that we may
# avoid issues with GIL deadlocks.
publish_proc = Process(target=publish_loop)
publish_proc.start()
# Initialize to first message.
first_msg = dut.WaitForMessage()
dut.get_mutable_context().SetTime(utime.GetTimeInSeconds(first_msg))
# Run to desired amount. (Anything more will cause interpreter to
# "freeze".)
dut.RunToSecondsAssumingInitialized(t_end)
publish_proc.join()

# Check expected values.
log_t_expected = np.array([4, 5, 6, 7, 8, 9])
log_t = logger.sample_times()
self.assertTrue(np.allclose(log_t_expected, log_t))
log_y = logger.data()
self.assertTrue(np.allclose(log_t_expected, log_y))
6 changes: 0 additions & 6 deletions bindings/pydrake/test/lcm_test.py
Original file line number Diff line number Diff line change
Expand Up @@ -4,8 +4,6 @@

from robotlocomotion import quaternion_t

from pydrake.common.test_utilities.deprecation import catch_drake_warnings


class TestLcm(unittest.TestCase):
def setUp(self):
Expand All @@ -19,10 +17,6 @@ def setUp(self):
def test_lcm(self):
dut = DrakeLcm()
self.assertIsInstance(dut, DrakeLcmInterface)
# Quickly start and stop the receiving thread.
with catch_drake_warnings(expected_count=2):
dut.StartReceiveThread()
dut.StopReceiveThread()
# Test virtual function names.
dut.Publish
dut.HandleSubscriptions
Expand Down
12 changes: 0 additions & 12 deletions lcm/BUILD.bazel
Original file line number Diff line number Diff line change
Expand Up @@ -17,7 +17,6 @@ drake_cc_package_library(
":drake_lcm",
":interface",
":lcm_log",
":lcm_receive_thread",
":mock",
":real",
],
Expand Down Expand Up @@ -46,7 +45,6 @@ drake_cc_library(
name = "real",
deps = [
":drake_lcm",
":lcm_receive_thread",
],
)

Expand All @@ -61,16 +59,6 @@ drake_cc_library(
],
)

drake_cc_library(
name = "lcm_receive_thread",
srcs = ["lcm_receive_thread.cc"],
hdrs = ["lcm_receive_thread.h"],
deps = [
"//common:essential",
"@lcm",
],
)

drake_cc_library(
name = "lcm_log",
srcs = ["drake_lcm_log.cc"],
Expand Down
Loading

0 comments on commit e128284

Please sign in to comment.