Skip to content

Commit

Permalink
systems/lcm: Deprecate lcm_driven_loop (RobotLocomotion#11281)
Browse files Browse the repository at this point in the history
  • Loading branch information
jwnimmer-tri authored Apr 22, 2019
1 parent e7846d7 commit 237d1c7
Show file tree
Hide file tree
Showing 7 changed files with 80 additions and 14 deletions.
33 changes: 28 additions & 5 deletions bindings/pydrake/systems/lcm_py.cc
Original file line number Diff line number Diff line change
Expand Up @@ -25,6 +25,11 @@ 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 @@ -68,6 +73,8 @@ class PySerializerInterface : public py::wrapper<SerializerInterface> {
}
};

#pragma GCC diagnostic push
#pragma GCC diagnostic ignored "-Wdeprecated-declarations"
class PyLcmMessageToTimeInterface
: public py::wrapper<LcmMessageToTimeInterface> {
public:
Expand All @@ -80,6 +87,7 @@ class PyLcmMessageToTimeInterface
double, LcmMessageToTimeInterface, GetTimeInSeconds, &abstract_value);
}
};
#pragma GCC diagnostic pop

} // namespace

Expand Down Expand Up @@ -129,13 +137,17 @@ PYBIND11_MODULE(lcm, m) {
}

{
#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);
doc.LcmMessageToTimeInterface.doc_deprecated);
#pragma GCC diagnostic pop
}

{
Expand Down Expand Up @@ -187,19 +199,29 @@ PYBIND11_MODULE(lcm, m) {
}

{
#pragma GCC diagnostic push
#pragma GCC diagnostic ignored "-Wdeprecated-declarations"
using Class = LcmDrivenLoop;
py::class_<Class>(m, "LcmDrivenLoop")
.def(py::init<const System<double>&, const LcmSubscriberSystem&,
std::unique_ptr<Context<double>>, DrakeLcm*,
std::unique_ptr<LcmMessageToTimeInterface>>(),
.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)
py::keep_alive<6, 1>(), doc.LcmDrivenLoop.ctor.doc_deprecated)
.def("WaitForMessage", &Class::WaitForMessage, py_reference_internal,
doc.LcmDrivenLoop.WaitForMessage.doc)
.def("RunToSecondsAssumingInitialized",
Expand All @@ -214,6 +236,7 @@ PYBIND11_MODULE(lcm, m) {
.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"),
Expand Down
9 changes: 6 additions & 3 deletions bindings/pydrake/systems/test/lcm_test.py
Original file line number Diff line number Diff line change
Expand Up @@ -177,7 +177,8 @@ def test_connect_lcm_scope(self):
def test_utime_to_seconds(self):
msg = header_t()
msg.utime = int(1e6)
dut = mut.PyUtimeMessageToSeconds(header_t)
with catch_drake_warnings(expected_count=1):
dut = mut.PyUtimeMessageToSeconds(header_t)
t_sec = dut.GetTimeInSeconds(AbstractValue.Make(msg))
self.assertEqual(t_sec, 1)

Expand Down Expand Up @@ -216,7 +217,8 @@ def _calc_output(self, context, output):

# Construct diagram for LcmDrivenLoop.
lcm = DrakeLcm(lcm_url)
utime = mut.PyUtimeMessageToSeconds(header_t)
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)
Expand All @@ -225,7 +227,8 @@ def _calc_output(self, context, output):
logger = LogOutput(dummy.get_output_port(0), builder)
logger.set_forced_publish_only()
diagram = builder.Build()
dut = mut.LcmDrivenLoop(diagram, sub, None, lcm, utime)
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
Expand Down
1 change: 1 addition & 0 deletions examples/humanoid_controller/BUILD.bazel
Original file line number Diff line number Diff line change
Expand Up @@ -135,6 +135,7 @@ drake_cc_binary(
srcs = [
"valkyrie_balancing_demo.cc",
],
copts = ["-Wno-deprecated-declarations"],
data = [
":config/valkyrie.alias_groups",
":config/valkyrie.id_controller_config",
Expand Down
4 changes: 4 additions & 0 deletions examples/kinova_jaco_arm/BUILD.bazel
Original file line number Diff line number Diff line change
Expand Up @@ -39,6 +39,10 @@ drake_cc_library(
drake_cc_binary(
name = "jaco_controller",
srcs = ["jaco_controller.cc"],
copts = [
# TODO(sammy-tri) Remove this once ported away from lcm_driven_loop.
"-Wno-deprecated-declarations",
],
data = [
"//manipulation/models/jaco_description:models",
],
Expand Down
5 changes: 5 additions & 0 deletions systems/lcm/BUILD.bazel
Original file line number Diff line number Diff line change
Expand Up @@ -168,6 +168,11 @@ drake_cc_library(

drake_cc_googletest(
name = "lcm_driven_loop_test",
copts = [
# The entire class under test is deprecated; when the class is removed,
# remove this entire unit test as well.
"-Wno-deprecated-declarations",
],
# TODO(jamiesnape, siyuanfeng-tri): Remove flaky flag, see #5936.
flaky = 1,
tags = [
Expand Down
6 changes: 3 additions & 3 deletions systems/lcm/lcm_driven_loop.cc
Original file line number Diff line number Diff line change
Expand Up @@ -4,6 +4,8 @@ namespace drake {
namespace systems {
namespace lcm {

#pragma GCC diagnostic push
#pragma GCC diagnostic ignored "-Wdeprecated-declarations"
LcmDrivenLoop::LcmDrivenLoop(
const System<double>& system, const LcmSubscriberSystem& driving_subscriber,
std::unique_ptr<Context<double>> context, drake::lcm::DrakeLcm* lcm,
Expand Down Expand Up @@ -31,11 +33,9 @@ LcmDrivenLoop::LcmDrivenLoop(
stepper_->Initialize();

// Starts the subscribing thread.
#pragma GCC diagnostic push
#pragma GCC diagnostic ignored "-Wdeprecated-declarations"
lcm_->StartReceiveThread();
#pragma GCC diagnostic pop
}
#pragma GCC diagnostic push

const AbstractValue& LcmDrivenLoop::WaitForMessage() {
driving_sub_.WaitForMessage(driving_sub_.GetMessageCount(*sub_context_));
Expand Down
36 changes: 33 additions & 3 deletions systems/lcm/lcm_driven_loop.h
Original file line number Diff line number Diff line change
Expand Up @@ -4,6 +4,7 @@
#include <memory>
#include <utility>

#include "drake/common/drake_deprecated.h"
#include "drake/lcm/drake_lcm.h"
#include "drake/systems/analysis/simulator.h"
#include "drake/systems/lcm/lcm_subscriber_system.h"
Expand All @@ -16,9 +17,16 @@ namespace lcm {
* A generic translator interface that extracts time in seconds from an
* abstract type.
*/
class LcmMessageToTimeInterface {
class DRAKE_DEPRECATED("2019-08-01",
"LcmDrivenLoop is deprecated with no direct replacement; "
"see https://github.com/RobotLocomotion/drake/pull/11281 for suggestions.")
LcmMessageToTimeInterface {
public:
#pragma GCC diagnostic push
#pragma GCC diagnostic ignored "-Wdeprecated-declarations"
DRAKE_NO_COPY_NO_MOVE_NO_ASSIGN(LcmMessageToTimeInterface)
#pragma GCC diagnostic pop

virtual ~LcmMessageToTimeInterface() {}

virtual double GetTimeInSeconds(
Expand All @@ -33,9 +41,16 @@ class LcmMessageToTimeInterface {
* is in micro seconds.
*/
template <typename MessageType>
class UtimeMessageToSeconds : public LcmMessageToTimeInterface {
class DRAKE_DEPRECATED("2019-08-01",
"LcmDrivenLoop is deprecated with no direct replacement; "
"see https://github.com/RobotLocomotion/drake/pull/11281 for suggestions.")
UtimeMessageToSeconds : public LcmMessageToTimeInterface {
public:
#pragma GCC diagnostic push
#pragma GCC diagnostic ignored "-Wdeprecated-declarations"
DRAKE_NO_COPY_NO_MOVE_NO_ASSIGN(UtimeMessageToSeconds)
#pragma GCC diagnostic pop

UtimeMessageToSeconds() {}
~UtimeMessageToSeconds() {}

Expand Down Expand Up @@ -101,8 +116,13 @@ class UtimeMessageToSeconds : public LcmMessageToTimeInterface {
* 3. The computation for the given system should be faster than the incoming
* message rate.
*/
class LcmDrivenLoop {
class DRAKE_DEPRECATED("2019-08-01",
"LcmDrivenLoop is deprecated with no direct replacement; "
"see https://github.com/RobotLocomotion/drake/pull/11281 for suggestions.")
LcmDrivenLoop {
public:
#pragma GCC diagnostic push
#pragma GCC diagnostic ignored "-Wdeprecated-declarations"
DRAKE_NO_COPY_NO_MOVE_NO_ASSIGN(LcmDrivenLoop)

/**
Expand All @@ -122,11 +142,15 @@ class LcmDrivenLoop {
* time stamp field that has consistent units. So extracting the time stamp
* depends on the concrete message content.
*/
DRAKE_DEPRECATED("2019-08-01",
"LcmDrivenLoop is deprecated with no direct replacement; "
"see https://github.com/RobotLocomotion/drake/pull/11281 for suggestions.")
LcmDrivenLoop(const System<double>& system,
const LcmSubscriberSystem& driving_subscriber,
std::unique_ptr<Context<double>> context,
drake::lcm::DrakeLcm* lcm,
std::unique_ptr<LcmMessageToTimeInterface> time_converter);
#pragma GCC diagnostic pop

/**
* Blocks the caller until a driving Lcm message is received, then returns
Expand Down Expand Up @@ -165,12 +189,15 @@ class LcmDrivenLoop {
return stepper_->get_mutable_context();
}

#pragma GCC diagnostic push
#pragma GCC diagnostic ignored "-Wdeprecated-declarations"
/**
* Returns a const reference to the message to seconds converter.
*/
const LcmMessageToTimeInterface& get_message_to_time_converter() const {
return *time_converter_;
}
#pragma GCC diagnostic pop

private:
// The handler system.
Expand All @@ -182,8 +209,11 @@ class LcmDrivenLoop {
// The lcm interface for publishing and subscribing.
drake::lcm::DrakeLcm* lcm_;

#pragma GCC diagnostic push
#pragma GCC diagnostic ignored "-Wdeprecated-declarations"
// Extracts time in seconds from received lcm messages.
std::unique_ptr<LcmMessageToTimeInterface> time_converter_;
#pragma GCC diagnostic pop

// If true, explicitly calls system_.Publish() after every step in the loop.
bool publish_on_every_received_message_{true};
Expand Down

0 comments on commit 237d1c7

Please sign in to comment.