From e128284d4da8c01344a3f795bc9e41b3c476cae1 Mon Sep 17 00:00:00 2001 From: Jeremy Nimmer Date: Thu, 1 Aug 2019 08:22:57 -0400 Subject: [PATCH] lcm: Remove deprecated methods (2019-08) (#11840) --- bindings/pydrake/BUILD.bazel | 1 - bindings/pydrake/lcm_py.cc | 24 +- bindings/pydrake/systems/_lcm_extra.py | 15 -- bindings/pydrake/systems/lcm_py.cc | 78 ------ bindings/pydrake/systems/test/lcm_test.py | 105 +------- bindings/pydrake/test/lcm_test.py | 6 - lcm/BUILD.bazel | 12 - lcm/drake_lcm.cc | 39 --- lcm/drake_lcm.h | 52 ---- lcm/lcm_receive_thread.cc | 37 --- lcm/lcm_receive_thread.h | 68 ----- lcm/test/drake_lcm_thread_test.cc | 26 +- systems/lcm/BUILD.bazel | 73 ------ systems/lcm/lcm_and_vector_base_translator.cc | 23 -- systems/lcm/lcm_and_vector_base_translator.h | 103 -------- systems/lcm/lcm_driven_loop.cc | 82 ------ systems/lcm/lcm_driven_loop.h | 233 ------------------ systems/lcm/lcmt_drake_signal_translator.cc | 76 ------ systems/lcm/lcmt_drake_signal_translator.h | 54 ---- systems/lcm/test/lcm_driven_loop_test.cc | 143 ----------- 20 files changed, 24 insertions(+), 1226 deletions(-) delete mode 100644 lcm/lcm_receive_thread.cc delete mode 100644 lcm/lcm_receive_thread.h delete mode 100644 systems/lcm/lcm_and_vector_base_translator.cc delete mode 100644 systems/lcm/lcm_and_vector_base_translator.h delete mode 100644 systems/lcm/lcm_driven_loop.cc delete mode 100644 systems/lcm/lcm_driven_loop.h delete mode 100644 systems/lcm/lcmt_drake_signal_translator.cc delete mode 100644 systems/lcm/lcmt_drake_signal_translator.h delete mode 100644 systems/lcm/test/lcm_driven_loop_test.cc diff --git a/bindings/pydrake/BUILD.bazel b/bindings/pydrake/BUILD.bazel index dbc9f5cc5ee4..c5185b0f773f 100644 --- a/bindings/pydrake/BUILD.bazel +++ b/bindings/pydrake/BUILD.bazel @@ -425,7 +425,6 @@ drake_py_unittest( name = "lcm_test", deps = [ ":lcm_py", - "//bindings/pydrake/common/test_utilities", "@lcmtypes_robotlocomotion//:lcmtypes_robotlocomotion_py", ], ) diff --git a/bindings/pydrake/lcm_py.cc b/bindings/pydrake/lcm_py.cc index bee9c765daec..8be6348698d9 100644 --- a/bindings/pydrake/lcm_py.cc +++ b/bindings/pydrake/lcm_py.cc @@ -49,28 +49,8 @@ PYBIND11_MODULE(lcm, m) { constexpr auto& cls_doc = doc.DrakeLcm; py::class_(m, "DrakeLcm", cls_doc.doc) .def(py::init<>(), cls_doc.ctor.doc_0args) - .def( - py::init(), 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(), py::arg("lcm_url"), + cls_doc.ctor.doc_1args); // TODO(eric.cousineau): Add remaining methods. } diff --git a/bindings/pydrake/systems/_lcm_extra.py b/bindings/pydrake/systems/_lcm_extra.py index 05abd632c655..f7f3bb500ac9 100644 --- a/bindings/pydrake/systems/_lcm_extra.py +++ b/bindings/pydrake/systems/_lcm_extra.py @@ -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. diff --git a/bindings/pydrake/systems/lcm_py.cc b/bindings/pydrake/systems/lcm_py.cc index fe0d2ac09a18..e50b2843664a 100644 --- a/bindings/pydrake/systems/lcm_py.cc +++ b/bindings/pydrake/systems/lcm_py.cc @@ -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" @@ -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 @@ -72,22 +65,6 @@ class PySerializerInterface : public py::wrapper { } }; -#pragma GCC diagnostic push -#pragma GCC diagnostic ignored "-Wdeprecated-declarations" -class PyLcmMessageToTimeInterface - : public py::wrapper { - public: - using Base = py::wrapper; - - 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) { @@ -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_( - m, "LcmMessageToTimeInterface") - .def(py::init([]() { - WarnDeprecated(kLcmDrivenLoopDeprecationString); - return std::make_unique(); - }), - doc.LcmMessageToTimeInterface.doc_deprecated); -#pragma GCC diagnostic pop - } - { using Class = LcmPublisherSystem; constexpr auto& cls_doc = doc.LcmPublisherSystem; @@ -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_(m, "LcmDrivenLoop") - .def( - py::init( - [](const System& system, - const LcmSubscriberSystem& driving_subscriber, - std::unique_ptr> context, DrakeLcm* lcm, - std::unique_ptr time_converter) { - WarnDeprecated(kLcmDrivenLoopDeprecationString); - return std::make_unique(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::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. diff --git a/bindings/pydrake/systems/test/lcm_test.py b/bindings/pydrake/systems/test/lcm_test.py index 703377e6aa64..214cb7c99c27 100644 --- a/bindings/pydrake/systems/test/lcm_test.py +++ b/bindings/pydrake/systems/test/lcm_test.py @@ -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() @@ -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)) diff --git a/bindings/pydrake/test/lcm_test.py b/bindings/pydrake/test/lcm_test.py index 370e6587cd92..275f8907d5d2 100644 --- a/bindings/pydrake/test/lcm_test.py +++ b/bindings/pydrake/test/lcm_test.py @@ -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): @@ -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 diff --git a/lcm/BUILD.bazel b/lcm/BUILD.bazel index 566670b452f0..22021f0214be 100644 --- a/lcm/BUILD.bazel +++ b/lcm/BUILD.bazel @@ -17,7 +17,6 @@ drake_cc_package_library( ":drake_lcm", ":interface", ":lcm_log", - ":lcm_receive_thread", ":mock", ":real", ], @@ -46,7 +45,6 @@ drake_cc_library( name = "real", deps = [ ":drake_lcm", - ":lcm_receive_thread", ], ) @@ -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"], diff --git a/lcm/drake_lcm.cc b/lcm/drake_lcm.cc index bea9d6db6936..0108849dbcb3 100644 --- a/lcm/drake_lcm.cc +++ b/lcm/drake_lcm.cc @@ -1,9 +1,7 @@ #include "drake/lcm/drake_lcm.h" #include -#include #include -#include #include #include @@ -49,11 +47,6 @@ class DrakeLcm::Impl { std::string lcm_url_; ::lcm::LCM lcm_; std::vector> subscriptions_; - - // TODO(jwnimmer-tri) To be removed once deprecated methods are gone. - std::unique_ptr receive_thread_; - // TODO(jwnimmer-tri) To be removed once deprecated methods are gone. - std::atomic_bool receive_thread_stopping_{false}; }; DrakeLcm::DrakeLcm() : DrakeLcm(std::string{}) {} @@ -67,32 +60,6 @@ DrakeLcm::DrakeLcm(std::string lcm_url) impl_->lcm_.getFileno(); } -// TODO(jwnimmer-tri) To be deprecated. -void DrakeLcm::StartReceiveThread() { - DRAKE_DEMAND(impl_->receive_thread_ == nullptr); - impl_->receive_thread_ = std::make_unique( - [this](){ - while (!this->impl_->receive_thread_stopping_) { - this->HandleSubscriptions(300); - } - }); -} - -// TODO(jwnimmer-tri) To be deprecated. -void DrakeLcm::StopReceiveThread() { - if (impl_->receive_thread_ != nullptr) { - impl_->receive_thread_stopping_ = true; - impl_->receive_thread_->join(); - impl_->receive_thread_stopping_ = false; - impl_->receive_thread_.reset(); - } -} - -// TODO(jwnimmer-tri) To be deprecated. -bool DrakeLcm::IsReceiveThreadRunning() const { - return impl_->receive_thread_ != nullptr; -} - std::string DrakeLcm::get_lcm_url() const { return impl_->lcm_url_; } @@ -261,12 +228,6 @@ 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_) { auto subscription = weak_subscription.lock(); diff --git a/lcm/drake_lcm.h b/lcm/drake_lcm.h index d1b2afee8785..e1fe1f2b14cc 100644 --- a/lcm/drake_lcm.h +++ b/lcm/drake_lcm.h @@ -6,7 +6,6 @@ #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 { @@ -36,57 +35,6 @@ class DrakeLcm : public DrakeLcmInterface { */ ~DrakeLcm() override; - /** - * (Advanced.) Starts the receive thread. Either HandleSubscriptions() xor - * this method must be called for subscribers to receive any messages. - * - * @warning Almost no Drake uses of LCM should require a background thread. - * Please use HandleSubscriptions() or systems::LcmInterfaceSystem instead. - * - * @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(); - - /** - * (Advanced.) Stops the receive thread. This must be called prior to any - * subscribers being destroyed. - * - * @warning Almost no Drake uses of LCM should require a background thread. - * Please use HandleSubscriptions() or systems::LcmInterfaceSystem instead. - * - * @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(); - - /** - * (Advanced.) Indicates that the receiving thread is running. - * - * @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; - /** * (Advanced.) An accessor to the underlying LCM instance. The returned * pointer is guaranteed to be valid for the duration of this object's diff --git a/lcm/lcm_receive_thread.cc b/lcm/lcm_receive_thread.cc deleted file mode 100644 index e0729583bc52..000000000000 --- a/lcm/lcm_receive_thread.cc +++ /dev/null @@ -1,37 +0,0 @@ -#include "drake/lcm/lcm_receive_thread.h" - -#include "drake/common/drake_assert.h" -#include "drake/common/text_logging.h" - -namespace drake { -namespace lcm { - -LcmReceiveThread::LcmReceiveThread(::lcm::LCM* lcm) : lcm_(lcm) { - DRAKE_DEMAND(lcm != nullptr); - lcm_thread_ = std::thread(&LcmReceiveThread::Looper, this); -} - -LcmReceiveThread::~LcmReceiveThread() { - Stop(); -} - -void LcmReceiveThread::Looper() { - while (!stop_) { - const int timeout_millis = 300; - const int count = lcm_->handleTimeout(timeout_millis); - if (count < 0) { - drake::log()->error("lcm::handleTimeout() error"); - return; - } - } -} - -void LcmReceiveThread::Stop() { - if (!stop_) { - stop_ = true; - lcm_thread_.join(); - } -} - -} // namespace lcm -} // namespace drake diff --git a/lcm/lcm_receive_thread.h b/lcm/lcm_receive_thread.h deleted file mode 100644 index d51490e917a8..000000000000 --- a/lcm/lcm_receive_thread.h +++ /dev/null @@ -1,68 +0,0 @@ -#pragma once - -#include -#include - -#include "lcm/lcm-cpp.hpp" - -#include "drake/common/drake_copyable.h" -#include "drake/common/drake_deprecated.h" - -namespace drake { -namespace lcm { - -/** - * (Advanced.) Maintains a thread that receives LCM messages and dispatches - * the messages to the appropriate message handlers. - * - * @warning Almost no Drake uses of LCM should require a background thread. - * Please use DrakeLcmInterface::HandleSubscriptions() or - * drake::systems::lcm::LcmInterfaceSystem instead. - */ -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: -#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. - * - * @param[in] lcm A pointer to the LCM instance through which to access the - * LCM network. This parameter cannot be `nullptr` and must remain valid for - * the lifetime of this object. - */ - explicit LcmReceiveThread(::lcm::LCM* lcm); - - /** - * The destructor that ensures the thread that receives LCM message is - * stopped. - */ - ~LcmReceiveThread(); - - /** - * Stops the LCM receive thread. This stops the reception of LCM messages. - */ - void Stop(); - - private: - // Loops waiting for LCM messages and dispatching them to the appropriate - // subscriber message handlers when they arrive. - void Looper(); - - // Whether to stop lcm_thread_. - std::atomic_bool stop_{false}; - - // A pointer to the LCM instance. - ::lcm::LCM* const lcm_{nullptr}; - - // The thread responsible for receiving LCM messages. - std::thread lcm_thread_; -}; - -} // namespace lcm -} // namespace drake diff --git a/lcm/test/drake_lcm_thread_test.cc b/lcm/test/drake_lcm_thread_test.cc index f915caf7751a..e802f4dbe0f4 100644 --- a/lcm/test/drake_lcm_thread_test.cc +++ b/lcm/test/drake_lcm_thread_test.cc @@ -1,3 +1,4 @@ +#include #include #include #include @@ -101,19 +102,18 @@ class DrakeLcmThreadTest : public ::testing::Test { // Call publish() until the mailbox matches our expected message. void LoopUntilDone(const MessageMailbox& mailbox, const std::function& 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 + // Launch a received thread until message_was_recived is done. + std::atomic_bool message_was_received{false}; + DrakeLcm* const dut = &dut_; + std::thread receive_thread([dut, &message_was_received]() { + while (!message_was_received) { + dut->HandleSubscriptions(300); + } + }); // Try until we're either done, or we timeout (5 seconds). const std::chrono::milliseconds kDelay(50); const int kMaxCount = 100; - bool message_was_received = false; int count = 0; while (!message_was_received && count++ < kMaxCount) { publish(); @@ -123,11 +123,9 @@ 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 + // Stop the thread. + message_was_received = true; + receive_thread.join(); } // The device under test. diff --git a/systems/lcm/BUILD.bazel b/systems/lcm/BUILD.bazel index eccfc060dee7..3806734ea7ae 100644 --- a/systems/lcm/BUILD.bazel +++ b/systems/lcm/BUILD.bazel @@ -14,15 +14,12 @@ drake_cc_package_library( name = "lcm", deps = [ ":connect_lcm_scope", - ":lcm_driven_loop", ":lcm_interface_system", ":lcm_log_playback_system", ":lcm_publisher_system", ":lcm_pubsub_system", ":lcm_subscriber_system", - ":lcmt_drake_signal_translator", ":serializer", - ":translator", ], ) @@ -42,23 +39,6 @@ drake_cc_library( ], ) -drake_cc_library( - name = "translator", - srcs = [ - "lcm_and_vector_base_translator.cc", - ], - hdrs = [ - "lcm_and_vector_base_translator.h", - ], - copts = [ - "-Wno-deprecated-declarations", - ], - deps = [ - "//common:essential", - "//systems/framework:vector", - ], -) - drake_cc_library( name = "serializer", srcs = ["serializer.cc"], @@ -125,61 +105,8 @@ drake_cc_library( ], ) -drake_cc_library( - name = "lcm_driven_loop", - srcs = [ - "lcm_driven_loop.cc", - ], - hdrs = [ - "lcm_driven_loop.h", - ], - deps = [ - ":lcm_pubsub_system", - "//lcm", - "//systems/analysis:simulator", - ], -) - -drake_cc_library( - name = "lcmt_drake_signal_translator", - srcs = ["lcmt_drake_signal_translator.cc"], - hdrs = ["lcmt_drake_signal_translator.h"], - copts = [ - "-Wno-deprecated-declarations", - ], - deps = [ - ":translator", - "//lcmtypes:drake_signal", - "//systems/framework:vector", - ], -) - # === test === -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 = [ - "no_asan", - "no_tsan", - "requires-network", - ], - deps = [ - "//common/test_utilities:eigen_matrix_compare", - "//lcm", - "//lcmtypes:drake_signal", - "//systems/framework", - "//systems/lcm:lcm_driven_loop", - "//systems/primitives:signal_logger", - ], -) - drake_cc_googletest( name = "lcm_interface_system_test", deps = [ diff --git a/systems/lcm/lcm_and_vector_base_translator.cc b/systems/lcm/lcm_and_vector_base_translator.cc deleted file mode 100644 index 6e5f7d22077f..000000000000 --- a/systems/lcm/lcm_and_vector_base_translator.cc +++ /dev/null @@ -1,23 +0,0 @@ -#include "drake/systems/lcm/lcm_and_vector_base_translator.h" - -namespace drake { -namespace systems { -namespace lcm { - -LcmAndVectorBaseTranslator::LcmAndVectorBaseTranslator(int size) - : size_(size) {} - -LcmAndVectorBaseTranslator::~LcmAndVectorBaseTranslator() {} - -int LcmAndVectorBaseTranslator::get_vector_size() const { - return size_; -} - -std::unique_ptr> -LcmAndVectorBaseTranslator::AllocateOutputVector() const { - return nullptr; -} - -} // namespace lcm -} // namespace systems -} // namespace drake diff --git a/systems/lcm/lcm_and_vector_base_translator.h b/systems/lcm/lcm_and_vector_base_translator.h deleted file mode 100644 index fde15f621022..000000000000 --- a/systems/lcm/lcm_and_vector_base_translator.h +++ /dev/null @@ -1,103 +0,0 @@ -#pragma once - -#include -#include -#include - -#include "drake/common/drake_copyable.h" -#include "drake/common/drake_deprecated.h" -#include "drake/systems/framework/basic_vector.h" - -namespace drake { -namespace systems { -namespace lcm { - -/** - * Defines an abstract parent class of all translators that convert between - * LCM message bytes and `drake::systems::VectorBase` objects. - */ -class DRAKE_DEPRECATED("2019-08-01", - "LcmAndVectorBaseTranslator is deprecated, with no replacement.") -LcmAndVectorBaseTranslator { - public: - DRAKE_NO_COPY_NO_MOVE_NO_ASSIGN(LcmAndVectorBaseTranslator) - - /** - * The constructor. - * - * @param[in] size The size of the vector in the `VectorBase`. - */ - DRAKE_DEPRECATED("2019-08-01", - "LcmAndVectorBaseTranslator is deprecated, with no replacement.") - explicit LcmAndVectorBaseTranslator(int size); - virtual ~LcmAndVectorBaseTranslator(); - - /** - * Returns the size of the vector in the `drake::systems::VectorBase` - * object. - */ - DRAKE_DEPRECATED("2019-08-01", - "LcmAndVectorBaseTranslator is deprecated, with no replacement.") - int get_vector_size() const; - - /** - * Allocates the vector storage for an output port of our LCM message type, - * in case special storage is needed. A result of nullptr indicates that no - * special vector is needed; the calling code can and should use a default - * vector implementation such as BasicVector. - * - * The default implementation in this class returns nullptr. Subclasses that - * require custom VectorBase subtypes should override it. - */ - DRAKE_DEPRECATED("2019-08-01", - "LcmAndVectorBaseTranslator is deprecated, with no replacement.") - virtual std::unique_ptr> AllocateOutputVector() const; - - /** - * Translates LCM message bytes into a `drake::systems::VectorBase` object. - * - * @param[in] lcm_message_bytes A pointer to a buffer holding the LCM - * message's data. - * - * @param[in] lcm_message_length The number of bytes pointed to by - * the @p lcm_message_bytes. - * - * @param[out] vector_base A pointer to where the translation of the LCM - * message should be stored. This pointer must not be `nullptr`. - * - * @throws std::runtime_error If a received LCM message failed to be decoded, - * or if the decoded LCM message is incompatible with the @p vector_base. - * This often occurs when the size of the @p vector_base does not equal - * or is incompatible with the size of the decoded LCM message. - */ - DRAKE_DEPRECATED("2019-08-01", - "LcmAndVectorBaseTranslator is deprecated, with no replacement.") - virtual void Deserialize( - const void* lcm_message_bytes, int lcm_message_length, - VectorBase* vector_base) const = 0; - - /** - * Translates a `drake::systems::VectorBase` object into LCM message bytes. - * - * @param[in] time The current time in seconds. This value is typically - * obtained from drake::systems::Context::get_time(). - * - * @param[in] vector_base The object to convert into an LCM message. - * - * @param[out] lcm_message_bytes The LCM message bytes. - * This pointer must not be `nullptr`. - */ - DRAKE_DEPRECATED("2019-08-01", - "LcmAndVectorBaseTranslator is deprecated, with no replacement.") - virtual void Serialize(double time, - const VectorBase& vector_base, - std::vector* lcm_message_bytes) const = 0; - - private: - // The size of the vector in the VectorBase. - const int size_; -}; - -} // namespace lcm -} // namespace systems -} // namespace drake diff --git a/systems/lcm/lcm_driven_loop.cc b/systems/lcm/lcm_driven_loop.cc deleted file mode 100644 index 8b20185721ed..000000000000 --- a/systems/lcm/lcm_driven_loop.cc +++ /dev/null @@ -1,82 +0,0 @@ -#include "drake/systems/lcm/lcm_driven_loop.h" - -namespace drake { -namespace systems { -namespace lcm { - -#pragma GCC diagnostic push -#pragma GCC diagnostic ignored "-Wdeprecated-declarations" -LcmDrivenLoop::LcmDrivenLoop( - const System& system, const LcmSubscriberSystem& driving_subscriber, - std::unique_ptr> context, drake::lcm::DrakeLcm* lcm, - std::unique_ptr time_converter) - : system_(system), - driving_sub_(driving_subscriber), - lcm_(lcm), - time_converter_(std::move(time_converter)), - stepper_( - std::make_unique>(system_, std::move(context))) { - DRAKE_DEMAND(lcm != nullptr); - DRAKE_DEMAND(time_converter_ != nullptr); - - // Allocates extra context and output just for the driving subscriber, so - // that this can explicitly query the message. - sub_context_ = driving_sub_.CreateDefaultContext(); - sub_output_ = driving_sub_.AllocateOutput(); - sub_swap_state_ = sub_context_->CloneState(); - sub_events_ = driving_sub_.AllocateCompositeEventCollection(); - - // Disables simulator's publish on its internal time step. - stepper_->set_publish_every_time_step(false); - stepper_->set_publish_at_initialization(false); - - stepper_->Initialize(); - - // Starts the subscribing thread. - lcm_->StartReceiveThread(); -} -#pragma GCC diagnostic push - -const AbstractValue& LcmDrivenLoop::WaitForMessage() { - driving_sub_.WaitForMessage(driving_sub_.GetMessageCount(*sub_context_)); - - driving_sub_.CalcNextUpdateTime(*sub_context_, sub_events_.get()); - - // If driving_sub_.WaitForMessage() returned, a message should be received - // and an event should be queued by driving_sub_.CalcNextUpdateTime(). - if (sub_events_->HasDiscreteUpdateEvents()) { - driving_sub_.CalcDiscreteVariableUpdates( - *sub_context_, sub_events_->get_discrete_update_events(), - &sub_swap_state_->get_mutable_discrete_state()); - } else if (sub_events_->HasUnrestrictedUpdateEvents()) { - driving_sub_.CalcUnrestrictedUpdate(*sub_context_, - sub_events_->get_unrestricted_update_events(), sub_swap_state_.get()); - } else { - DRAKE_DEMAND(false); - } - sub_context_->get_mutable_state().SetFrom(*sub_swap_state_); - - driving_sub_.CalcOutput(*sub_context_, sub_output_.get()); - return *(sub_output_->get_data(0)); -} - -void LcmDrivenLoop::RunToSecondsAssumingInitialized(double stop_time) { - double msg_time; - - while (true) { - msg_time = time_converter_->GetTimeInSeconds(WaitForMessage()); - if (msg_time >= stop_time) break; - - stepper_->AdvanceTo(msg_time); - - // Explicitly publish after we are done with all the intermediate - // computation. - if (publish_on_every_received_message_) { - system_.Publish(stepper_->get_context()); - } - } -} - -} // namespace lcm -} // namespace systems -} // namespace drake diff --git a/systems/lcm/lcm_driven_loop.h b/systems/lcm/lcm_driven_loop.h deleted file mode 100644 index 3d0a51fc0152..000000000000 --- a/systems/lcm/lcm_driven_loop.h +++ /dev/null @@ -1,233 +0,0 @@ -#pragma once - -#include -#include -#include - -#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" - -namespace drake { -namespace systems { -namespace lcm { - -/** - * A generic translator interface that extracts time in seconds from an - * abstract type. - */ -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( - const AbstractValue& abstract_value) const = 0; - - protected: - LcmMessageToTimeInterface() {} -}; - -/** - * A translator class for Lcm message types that have a "utime" field, which - * is in micro seconds. - */ -template -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() {} - - double GetTimeInSeconds(const AbstractValue& abstract_value) const override { - const MessageType& msg = abstract_value.get_value(); - return static_cast(msg.utime) / 1e6; - } -}; - -/** - * This class implements a loop that's driven by a Lcm message. The context time - * is explicitly slaved to the time in the received Lcm message. This class is - * intended to provide a generalized way to implement a message handling loop: - * an input message arrives, from which a response is computed and published. - * A common use case is to implement a distributed controller for a physical - * robot, where low level communication with the hardware is handled in the - * device driver (a separate process than the controller). The device driver - * sends a message containing the estimated state. The controller processes - * that message and sends back a command in response. The device driver finally - * receives and executes the command. - * - * This class is designed to be agnostic to different types of the driving Lcm - * message to provide a generic API. The Lcm message is internally encapsulated - * in AbstractValue, which erases its type. In addition, the message time stamp - * is the only required information by this class, which can be extracted by - * an instance of LcmMessageToTimeInterface. It is assumed that the caller knows - * the concrete type of the message, and is able to supply a time converter. - * - * This class uses the Simulator class internally for event handling - * (publish, discrete update, and unrestricted update) and - * continuous state integration (e.g. the I term in a PID). The main message - * handling loop conceptually is: - *
- * while(context.time < stop_time) {
- *   msg = wait_for_message("channel");
- *   simulator.AdvanceTo(msg.time);
- *   if (publish) {
- *     system.Publish(simulator.context);
- *   }
- * }
- * 
- * - * Since time is slaved to some outside source, the user needs to be mindful of - * `system`'s configuration especially about event timing. For example, let us - * assume that `system` is configured to perform a discrete time action every - * 5ms (at 200Hz), and the necessary computation for `system` to step forward - * in time is very small. Now, suppose the driving message arrives at 1 Hz in - * real time. One would observe 200 such actions occur in rapid succession - * followed by nearly one second of silence. This is because - * `msg = wait_for_message("channel")` takes about one second in real time, - * and `simulator.AdvanceTo(msg.time)`, which forwards the simulator's clock by - * one second and performs 200 actions takes about 0 seconds in real time. - * The root cause is that the 200Hz rate of the handler system is tied to the - * internal virtual clock rather than real time. This problem is less - * significant when the computation time for handling one message is roughly - * the same as the interval between consecutive driving messages. - * - * This implementation relies on several assumptions: - * - * 1. The loop is blocked only on one Lcm message. - * 2. It's pointless for the handler system to perform any computation - * without a new Lcm message, thus the handler loop is blocking. - * 3. The computation for the given system should be faster than the incoming - * message rate. - */ -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) - - /** - * Constructor. - * @param system Const reference to the handler system. Its life span must be - * longer than `this`. - * @param driving_subscriber Const reference to the driving subscriber. Its - * life span must be longer than `this`. - * @param context Unique pointer to a context allocated for @p system. Can be - * nullptr, in which case a context will be allocated internally. - * @param lcm Pointer to Lcm interface. Its life span must be longer than - * `this`. @p lcm cannot be nullptr, otherwise aborts. - * @param time_converter Unique pointer to a converter that extracts time in - * seconds from the driving message time. Cannot be nullptr, otherwise `this` - * aborts. @p time_converter is necessary because of two reasons. 1: The Lcm - * message type agnostic design of this class. 2: Lcm messages lack a uniform - * 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& system, - const LcmSubscriberSystem& driving_subscriber, - std::unique_ptr> context, - drake::lcm::DrakeLcm* lcm, - std::unique_ptr time_converter); -#pragma GCC diagnostic pop - - /** - * Blocks the caller until a driving Lcm message is received, then returns - * a const reference of AbstractValue to that message. The call is assumed - * to know the type of the actual message and have means to inspect the - * message. - */ - // TODO(siyuan): add a time out version. - const AbstractValue& WaitForMessage(); - - /** - * Starts the message handling loop assuming the context (e.g. state and - * time) has already been properly initialized by the caller if necessary. - * @param stop_time End time in seconds relative to the time stamp in the - * driving Lcm message. - * @note If the latest driving time is the same as `stop_time`, then no - * stepping will occur. - */ - void RunToSecondsAssumingInitialized( - double stop_time = std::numeric_limits::infinity()); - - /** - * Sets a flag that forces Publish() at the very beginning of the message - * handling loop as well as inside the loop. To achieve "publish whenever - * a new message has been handled", the user needs to make sure that no - * subsystems have declared period publish, and @p flag is true. - */ - void set_publish_on_every_received_message(bool flag) { - publish_on_every_received_message_ = flag; - } - - /** - * Returns a mutable reference to the context. - */ - Context& get_mutable_context() { - 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. - const System& system_; - - // The message subscriber. - const LcmSubscriberSystem& driving_sub_; - - // 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 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}; - - // Reusing the simulator to manage event handling and state progression. - std::unique_ptr> stepper_; - - // Separate context and output port for the driving subscriber. - std::unique_ptr> sub_context_; - std::unique_ptr> sub_output_; - std::unique_ptr> sub_swap_state_; - std::unique_ptr> sub_events_; -}; - -} // namespace lcm -} // namespace systems -} // namespace drake diff --git a/systems/lcm/lcmt_drake_signal_translator.cc b/systems/lcm/lcmt_drake_signal_translator.cc deleted file mode 100644 index f932260fcf7c..000000000000 --- a/systems/lcm/lcmt_drake_signal_translator.cc +++ /dev/null @@ -1,76 +0,0 @@ -#include "drake/systems/lcm/lcmt_drake_signal_translator.h" - -#include -#include - -#include "lcm/lcm-cpp.hpp" - -#include "drake/common/drake_assert.h" -#include "drake/lcmt_drake_signal.hpp" -#include "drake/systems/framework/basic_vector.h" - -namespace drake { -namespace systems { -namespace lcm { - -using std::runtime_error; - -void LcmtDrakeSignalTranslator::Deserialize( - const void* lcm_message_bytes, int lcm_message_length, - VectorBase* vector_base) const { - DRAKE_DEMAND(vector_base); - - // Decodes the LCM message using data from the receive buffer. - drake::lcmt_drake_signal message; - int status = message.decode(lcm_message_bytes, 0, lcm_message_length); - if (status < 0) { - throw runtime_error( - "drake::systems::lcm::LcmtDrakeSignalTranslator: Deserialize: ERROR: " - "Failed to decode LCM message, the status is " + - std::to_string(status) + "."); - } - - // Verifies that the LCM message and vector_base both have the same size. - // Throws an exception if the sizes do not match. - if (message.dim != vector_base->size()) { - throw runtime_error( - "drake::systems::lcm::LcmtDrakeSignalTranslator: Deserialize: ERROR: " - "The LCM message's size (" + std::to_string(message.dim) + ") is not " - "equal to vector_base's size (" + - std::to_string(vector_base->size()) + ")."); - } - - // Saves the values from the LCM message into vector_base. - // Assumes that the order of the values are identical in both. - for (int i = 0; i < message.dim; ++i) { - vector_base->SetAtIndex(i, message.val[i]); - } -} - -void LcmtDrakeSignalTranslator::Serialize(double time, - const VectorBase& vector_base, - std::vector* lcm_message_bytes) const { - DRAKE_ASSERT(vector_base.size() == get_vector_size()); - DRAKE_ASSERT(lcm_message_bytes != nullptr); - - // Instantiates and initializes an LCM message with the state of vector_base. - drake::lcmt_drake_signal message; - message.dim = vector_base.size(); - message.val.resize(message.dim); - message.coord.resize(message.dim); - message.timestamp = static_cast(time * 1000); - - for (int i = 0; i < message.dim; ++i) { - message.val[i] = vector_base.GetAtIndex(i); - message.coord[i] = ""; - } - - // Serializes the LCM message into a vector of bytes. - const int lcm_message_length = message.getEncodedSize(); - lcm_message_bytes->resize(lcm_message_length); - message.encode(lcm_message_bytes->data(), 0, lcm_message_length); -} - -} // namespace lcm -} // namespace systems -} // namespace drake diff --git a/systems/lcm/lcmt_drake_signal_translator.h b/systems/lcm/lcmt_drake_signal_translator.h deleted file mode 100644 index b65a606eadb8..000000000000 --- a/systems/lcm/lcmt_drake_signal_translator.h +++ /dev/null @@ -1,54 +0,0 @@ -#pragma once - -#include -#include - -#include "drake/common/drake_copyable.h" -#include "drake/systems/framework/vector_base.h" -#include "drake/systems/lcm/lcm_and_vector_base_translator.h" - -namespace drake { -namespace systems { -namespace lcm { - -/** - * Specializes LcmAndVectorBaseTranslator to handle LCM messages of type - * `drake::lcmt_drake_signal`. - * - * Assumes the number and order of values in the LCM message and the - * drake::systems::VectorBase are identical. - */ -class DRAKE_DEPRECATED("2019-08-01", - "LcmtDrakeSignalTranslator is deprecated, with no replacement.") -LcmtDrakeSignalTranslator : public LcmAndVectorBaseTranslator { - public: - DRAKE_NO_COPY_NO_MOVE_NO_ASSIGN(LcmtDrakeSignalTranslator) - - /** - * A constructor that sets the expected sizes of the LCM message and the - * VectorBase. Both the LCM message and VectorBase must be the same size. - * - * @param[in] size The number of elements in both `VectorBase` and - * `drake::lcmt_drake_signal`. - */ - DRAKE_DEPRECATED("2019-08-01", - "LcmtDrakeSignalTranslator is deprecated, with no replacement.") - explicit LcmtDrakeSignalTranslator(int size) - : LcmAndVectorBaseTranslator(size) {} - - DRAKE_DEPRECATED("2019-08-01", - "LcmtDrakeSignalTranslator is deprecated, with no replacement.") - void Deserialize( - const void* lcm_message_bytes, int lcm_message_length, - VectorBase* vector_base) const override; - - DRAKE_DEPRECATED("2019-08-01", - "LcmtDrakeSignalTranslator is deprecated, with no replacement.") - void Serialize(double time, - const VectorBase& vector_base, - std::vector* lcm_message_bytes) const override; -}; - -} // namespace lcm -} // namespace systems -} // namespace drake diff --git a/systems/lcm/test/lcm_driven_loop_test.cc b/systems/lcm/test/lcm_driven_loop_test.cc deleted file mode 100644 index d4aa4ae7b68b..000000000000 --- a/systems/lcm/test/lcm_driven_loop_test.cc +++ /dev/null @@ -1,143 +0,0 @@ -#include "drake/systems/lcm/lcm_driven_loop.h" - -#include -#include "lcm/lcm-cpp.hpp" - -#include "drake/common/test_utilities/eigen_matrix_compare.h" -#include "drake/lcm/drake_lcm.h" -#include "drake/lcmt_drake_signal.hpp" -#include "drake/systems/framework/diagram_builder.h" -#include "drake/systems/primitives/signal_logger.h" - -namespace drake { -namespace systems { -namespace lcm { -namespace { - -const int kStart = 3; -const int kEnd = 10; -// Use a slight perturbation of the default URL. -// TODO(eric.cousineau): Make this URL be unique to each workspace / test run. -const char kLcmUrl[] = "udpm://239.255.76.67:7668"; - -// Converts millisecond timestamp field to second. -class MilliSecTimeStampMessageToSeconds : public LcmMessageToTimeInterface { - public: - DRAKE_NO_COPY_NO_MOVE_NO_ASSIGN(MilliSecTimeStampMessageToSeconds) - MilliSecTimeStampMessageToSeconds() {} - ~MilliSecTimeStampMessageToSeconds() {} - - double GetTimeInSeconds(const AbstractValue& abstract_value) const override { - const auto& msg = abstract_value.get_value(); - return static_cast(msg.timestamp) / 1e3; - } -}; - -// A dummy test system that outputs the input message's time stamp in seconds. -class DummySys : public systems::LeafSystem { - public: - DRAKE_NO_COPY_NO_MOVE_NO_ASSIGN(DummySys); - DummySys() { - DeclareAbstractInputPort("lcmt_drake_signal", Value()); - DeclareVectorOutputPort(systems::BasicVector(1), - &DummySys::CalcTimestamp); - } - - void CalcTimestamp(const systems::Context& context, - systems::BasicVector* output) const { - const lcmt_drake_signal& msg = - this->get_input_port(0).Eval(context); - auto out_vector = output->get_mutable_value(); - out_vector(0) = static_cast(msg.timestamp) / 1e3; - } -}; - -// Dummy publish thread. Usleeps so that the dut thread has enough time to -// process. -void publish() { - ::lcm::LCM lcm(kLcmUrl); - lcmt_drake_signal msg; - msg.dim = 0; - msg.val.resize(msg.dim); - msg.coord.resize(msg.dim); - - const int kSleepMicroSec = 100000; - - // This thread will first sleep for long enough to ensure `sys` will always - // receive the first message for test consistency. In practice, this is - // less important if `sys` does not need to receive the very first published - // message. - usleep(kSleepMicroSec); - - for (int i = kStart; i <= kEnd; i++) { - msg.timestamp = 1000 * i; - lcm.publish("test", &msg); - usleep(kSleepMicroSec); - } -} - -// The receiving Diagram in this test consists of a LcmSubscriberSystem, -// a DummySys and a SignalLogger. The intended behavior is that every time -// a new Lcm message arrives, its timestamp will be logged by the SignalLogger. -GTEST_TEST(LcmDrivenLoopTest, TestLoop) { - drake::lcm::DrakeLcm lcm(kLcmUrl); - DiagramBuilder builder; - - // Makes the test system. - auto sub = builder.AddSystem( - LcmSubscriberSystem::Make("test", &lcm)); - sub->set_name("subscriber"); - auto dummy = builder.AddSystem(); - dummy->set_name("dummy"); - - auto logger = builder.AddSystem>(1); - logger->set_name("logger"); - logger->set_forced_publish_only(); // Log only when told to do so. - - builder.Connect(*sub, *dummy); - builder.Connect(*dummy, *logger); - auto sys = builder.Build(); - - // Makes the lcm driven loop. - lcm::LcmDrivenLoop dut(*sys, *sub, nullptr, &lcm, - std::make_unique()); - // This ensures that dut calls sys->Publish() (a.k.a. "forced publish") - // every time it handles a message, which triggers the logger to save its - // input (message time stamp) to the log. - dut.set_publish_on_every_received_message(true); - - // Starts the publishing thread. - std::thread pub_thread(&publish); - - // Waits for the first message. - const AbstractValue& first_msg = dut.WaitForMessage(); - double msg_time = - dut.get_message_to_time_converter().GetTimeInSeconds(first_msg); - dut.get_mutable_context().SetTime(msg_time); - - // Starts the loop. - dut.RunToSecondsAssumingInitialized(static_cast(kEnd)); - - // Reaps the publishing thread. - pub_thread.join(); - - // Makes the expected output: should be [kStart + 1, ... kEnd]. kStart is - // used to initialize the loop's initial context, so it's not used for - // computation, thus is not reflected in the output. - VectorX expected(kEnd - kStart - 1); - int ctr = 0; - for (int i = kStart + 1; i < kEnd; i++) { - expected(ctr++) = i; - } - - // Compare logger's data, which are the message time stamps. They should - // match the values set in the publishing thread. - EXPECT_TRUE(drake::CompareMatrices(expected.transpose(), logger->data(), - 1e-12, - drake::MatrixCompareType::absolute)); -} - -} // namespace -} // namespace lcm -} // namespace systems -} // namespace drake