From 8c78a64bf204426dfbfd1ff3251c6af810743b7a Mon Sep 17 00:00:00 2001 From: Jeremy Nimmer Date: Sat, 30 Dec 2023 08:51:01 -0800 Subject: [PATCH] [lcm] Remove deprecated code 2024-01 Remove deprecated access to underlying native LCM C++ object. Adjust DrakeLcmLog implementation to avoid calling LCM's C++ code. The C++ code is not ABI-stable. (This was missed in d34b2dca.) --- lcm/drake_lcm.cc | 10 +--- lcm/drake_lcm.h | 22 +------- lcm/drake_lcm_log.cc | 33 ++++++------ lcm/test/drake_lcm_test.cc | 54 ++++++++----------- .../libdrake/test/exported_symbols_test.py | 2 - 5 files changed, 44 insertions(+), 77 deletions(-) diff --git a/lcm/drake_lcm.cc b/lcm/drake_lcm.cc index 4cb93ef18d29..044cdb6021de 100644 --- a/lcm/drake_lcm.cc +++ b/lcm/drake_lcm.cc @@ -7,7 +7,6 @@ #include #include -#include // N.B. C++ is used only by get_lcm_instance(). #include #include "drake/common/drake_assert.h" @@ -82,7 +81,6 @@ class DrakeLcm::Impl { std::string lcm_url_; bool deferred_initialization_{}; lcm_t* lcm_{}; - std::unique_ptr<::lcm::LCM> lcm_cpp_; // Typically nullptr. const std::string channel_suffix_; std::vector> subscriptions_; std::string handle_subscriptions_error_message_; @@ -108,12 +106,8 @@ std::string DrakeLcm::get_lcm_url() const { return impl_->lcm_url_; } -::lcm::LCM* DrakeLcm::get_native() { - if (impl_->lcm_cpp_ == nullptr) { - // Create the C++ wrapper only when requested by the user or our unit test. - impl_->lcm_cpp_ = std::make_unique<::lcm::LCM>(impl_->lcm_); - } - return impl_->lcm_cpp_.get(); +void* DrakeLcm::get_native_lcm_handle_for_unit_testing() { + return impl_->lcm_; } void DrakeLcm::Publish(const std::string& channel, const void* data, diff --git a/lcm/drake_lcm.h b/lcm/drake_lcm.h index cbbf62256eb1..d7ff7062ff93 100644 --- a/lcm/drake_lcm.h +++ b/lcm/drake_lcm.h @@ -6,19 +6,9 @@ #include #include "drake/common/drake_copyable.h" -#include "drake/common/drake_deprecated.h" #include "drake/lcm/drake_lcm_interface.h" #include "drake/lcm/drake_lcm_params.h" -#ifndef DRAKE_DOXYGEN_CXX -namespace lcm { -// We don't want to pollute our Drake headers with the include paths for either -// @lcm or @glib, so we forward-declare the `class ::lcm::LCM` for use only by -// DrakeLcm::get_native() -- an unit-test-only private function. -class LCM; -} // namespace lcm -#endif - namespace drake { namespace lcm { @@ -54,16 +44,6 @@ class DrakeLcm : public DrakeLcmInterface { */ ~DrakeLcm() override; - DRAKE_DEPRECATED( - "2024-01-01", - "Drake will no longer provide access to the underlying lcm::LCM object.") - /** - * (Advanced.) An accessor to the underlying LCM instance. The returned - * pointer is guaranteed to be valid for the duration of this object's - * lifetime. - */ - ::lcm::LCM* get_lcm_instance() { return get_native(); } - void Publish(const std::string&, const void*, int, std::optional) override; std::string get_lcm_url() const override; @@ -80,7 +60,7 @@ class DrakeLcm : public DrakeLcmInterface { void OnHandleSubscriptionsError(const std::string&) override; - ::lcm::LCM* get_native(); + void* get_native_lcm_handle_for_unit_testing(); class Impl; std::unique_ptr impl_; diff --git a/lcm/drake_lcm_log.cc b/lcm/drake_lcm_log.cc index 54a8b176433c..9d2026f240d7 100644 --- a/lcm/drake_lcm_log.cc +++ b/lcm/drake_lcm_log.cc @@ -7,7 +7,7 @@ #include #include -#include "lcm/lcm-cpp.hpp" +#include "lcm/lcm.h" #include "drake/common/drake_assert.h" @@ -22,8 +22,10 @@ class DrakeLcmLog::Impl { public: std::multimap subscriptions_; std::vector multichannel_subscriptions_; - std::unique_ptr<::lcm::LogFile> log_; - const ::lcm::LogEvent* next_event_{nullptr}; + std::unique_ptr<::lcm_eventlog_t, decltype(&::lcm_eventlog_destroy)> // BR + log_{nullptr, &::lcm_eventlog_destroy}; + std::unique_ptr<::lcm_eventlog_event_t, decltype(&::lcm_eventlog_free_event)> + next_event_{nullptr, &::lcm_eventlog_free_event}; }; DrakeLcmLog::DrakeLcmLog(const std::string& file_name, bool is_write, @@ -34,12 +36,12 @@ DrakeLcmLog::DrakeLcmLog(const std::string& file_name, bool is_write, url_("lcmlog://" + file_name), impl_(new Impl) { if (is_write_) { - impl_->log_ = std::make_unique<::lcm::LogFile>(file_name, "w"); + impl_->log_.reset(lcm_eventlog_create(file_name.c_str(), "w")); } else { - impl_->log_ = std::make_unique<::lcm::LogFile>(file_name, "r"); - impl_->next_event_ = impl_->log_->readNextEvent(); + impl_->log_.reset(lcm_eventlog_create(file_name.c_str(), "r")); + impl_->next_event_.reset(lcm_eventlog_read_next_event(impl_->log_.get())); } - if (!impl_->log_->good()) { + if (impl_->log_ == nullptr) { throw std::runtime_error("Failed to open log file: " + file_name); } } @@ -56,20 +58,20 @@ void DrakeLcmLog::Publish(const std::string& channel, const void* data, throw std::logic_error("Publish is only available for log saving."); } - ::lcm::LogEvent log_event{}; + ::lcm_eventlog_event_t log_event{}; if (!overwrite_publish_time_with_system_clock_) { log_event.timestamp = second_to_timestamp(time_sec.value_or(0.0)); } else { log_event.timestamp = std::chrono::steady_clock::now().time_since_epoch() / std::chrono::microseconds(1); } - log_event.channel = channel; + log_event.channellen = channel.size(); + log_event.channel = const_cast(channel.c_str()); log_event.datalen = data_size; log_event.data = const_cast(data); - std::lock_guard lock(mutex_); // TODO(siyuan): should make cache this or thread write this. - if (impl_->log_->writeEvent(&log_event) != 0) { + if (::lcm_eventlog_write_event(impl_->log_.get(), &log_event) != 0) { throw std::runtime_error("Publish failed to write to log file."); } } @@ -132,7 +134,7 @@ void DrakeLcmLog::DispatchMessageAndAdvanceLog(double current_time) { if (impl_->next_event_ == nullptr) { return; } - const ::lcm::LogEvent& next_event = *impl_->next_event_; + const ::lcm_eventlog_event_t& next_event = *impl_->next_event_; // Do nothing if the call time does not match the event's time. if (current_time != timestamp_to_second(next_event.timestamp)) { @@ -140,17 +142,18 @@ void DrakeLcmLog::DispatchMessageAndAdvanceLog(double current_time) { } // Dispatch message if necessary. - const auto& range = impl_->subscriptions_.equal_range(next_event.channel); + const std::string channel(next_event.channel, next_event.channellen); + const auto& range = impl_->subscriptions_.equal_range(channel); for (auto iter = range.first; iter != range.second; ++iter) { const HandlerFunction& handler = iter->second; handler(next_event.data, next_event.datalen); } for (const auto& multi_handler : impl_->multichannel_subscriptions_) { - multi_handler(next_event.channel, next_event.data, next_event.datalen); + multi_handler(channel, next_event.data, next_event.datalen); } // Advance log. - impl_->next_event_ = impl_->log_->readNextEvent(); + impl_->next_event_.reset(lcm_eventlog_read_next_event(impl_->log_.get())); } void DrakeLcmLog::OnHandleSubscriptionsError(const std::string& error_message) { diff --git a/lcm/test/drake_lcm_test.cc b/lcm/test/drake_lcm_test.cc index 6d5c7f695ef0..036a145d8973 100644 --- a/lcm/test/drake_lcm_test.cc +++ b/lcm/test/drake_lcm_test.cc @@ -17,9 +17,10 @@ namespace lcm { class DrakeLcmTester { public: DrakeLcmTester() = delete; - static ::lcm::LCM* get_native(DrakeLcm* dut) { + static ::lcm::LCM get_native(DrakeLcm* dut) { DRAKE_DEMAND(dut != nullptr); - return dut->get_native(); + return ::lcm::LCM( + static_cast<::lcm_t*>(dut->get_native_lcm_handle_for_unit_testing())); } }; namespace { @@ -59,7 +60,8 @@ class DrakeLcmTest : public ::testing::Test { EXPECT_TRUE(message_was_received); } - ::lcm::LCM* get_native() { return DrakeLcmTester::get_native(dut_.get()); } + // Returns a C++ interface wrapper around DrakeLcm's internal LCM object. + ::lcm::LCM get_native() { return DrakeLcmTester::get_native(dut_.get()); } // The device under test. std::unique_ptr dut_ = std::make_unique(); @@ -105,7 +107,7 @@ TEST_F(DrakeLcmTest, EmptyChannelTest) { // Tests DrakeLcm's ability to publish an LCM message. // We subscribe using the native LCM APIs. TEST_F(DrakeLcmTest, PublishTest) { - ::lcm::LCM* const native_lcm = get_native(); + ::lcm::LCM native_lcm = get_native(); const std::string channel_name = "DrakeLcmTest.PublishTest"; lcmt_drake_signal received{}; @@ -115,18 +117,18 @@ TEST_F(DrakeLcmTest, PublishTest) { DRAKE_DEMAND(new_value != nullptr); received = *new_value; }; - native_lcm->subscribe(channel_name, std::move(handler)); + native_lcm.subscribe(channel_name, std::move(handler)); LoopUntilDone(&received, 20 /* retries */, [&]() { Publish(dut_.get(), channel_name, message_); - native_lcm->handleTimeout(50 /* millis */); + native_lcm.handleTimeout(50 /* millis */); }); } // Tests DrakeLcm's ability to subscribe to an LCM message. // We publish using the native LCM APIs. TEST_F(DrakeLcmTest, SubscribeTest) { - ::lcm::LCM* const native_lcm = get_native(); + ::lcm::LCM native_lcm = get_native(); const std::string channel_name = "DrakeLcmTest.SubscribeTest"; lcmt_drake_signal received{}; @@ -138,7 +140,7 @@ TEST_F(DrakeLcmTest, SubscribeTest) { int total = 0; LoopUntilDone(&received, 20 /* retries */, [&]() { - native_lcm->publish(channel_name, &message_); + native_lcm.publish(channel_name, &message_); total += dut_->HandleSubscriptions(50 /* millis */); }); EXPECT_EQ(total, 1); @@ -146,7 +148,7 @@ TEST_F(DrakeLcmTest, SubscribeTest) { // Repeats the above test, but with explicit opt-out of unsubscribe. TEST_F(DrakeLcmTest, SubscribeTest2) { - ::lcm::LCM* const native_lcm = get_native(); + ::lcm::LCM native_lcm = get_native(); const std::string channel_name = "DrakeLcmTest.SubscribeTest2"; lcmt_drake_signal received{}; @@ -159,7 +161,7 @@ TEST_F(DrakeLcmTest, SubscribeTest2) { int total = 0; LoopUntilDone(&received, 20 /* retries */, [&]() { - native_lcm->publish(channel_name, &message_); + native_lcm.publish(channel_name, &message_); total += dut_->HandleSubscriptions(50 /* millis */); }); EXPECT_EQ(total, 1); @@ -167,7 +169,7 @@ TEST_F(DrakeLcmTest, SubscribeTest2) { // Repeat SubscribeTest for SubscribeAllChannels. TEST_F(DrakeLcmTest, SubscribeAllTest) { - ::lcm::LCM* const native_lcm = get_native(); + ::lcm::LCM native_lcm = get_native(); const std::string channel_name = "DrakeLcmTest.SubscribeAllTest"; lcmt_drake_signal received{}; @@ -181,7 +183,7 @@ TEST_F(DrakeLcmTest, SubscribeAllTest) { int total = 0; LoopUntilDone(&received, 20 /* retries */, [&]() { - native_lcm->publish(channel_name, &message_); + native_lcm.publish(channel_name, &message_); total += dut_->HandleSubscriptions(50 /* millis */); }); EXPECT_EQ(total, 1); @@ -189,7 +191,7 @@ TEST_F(DrakeLcmTest, SubscribeAllTest) { // Repeat SubscribeTest2 for SubscribeAllChannels. TEST_F(DrakeLcmTest, SubscribeAllTest2) { - ::lcm::LCM* const native_lcm = get_native(); + ::lcm::LCM native_lcm = get_native(); const std::string channel_name = "DrakeLcmTest.SubscribeAllTest2"; lcmt_drake_signal received{}; @@ -204,7 +206,7 @@ TEST_F(DrakeLcmTest, SubscribeAllTest2) { int total = 0; LoopUntilDone(&received, 20 /* retries */, [&]() { - native_lcm->publish(channel_name, &message_); + native_lcm.publish(channel_name, &message_); total += dut_->HandleSubscriptions(50 /* millis */); }); EXPECT_EQ(total, 1); @@ -369,7 +371,7 @@ TEST_F(DrakeLcmTest, Suffix) { DrakeLcmParams params; params.channel_suffix = "_SUFFIX"; dut_ = std::make_unique(params); - ::lcm::LCM* const native_lcm = get_native(); + ::lcm::LCM native_lcm = get_native(); // Subscribe using native LCM (with the fully-qualified channel name). lcmt_drake_signal received_native{}; @@ -379,7 +381,7 @@ TEST_F(DrakeLcmTest, Suffix) { DRAKE_DEMAND(new_value != nullptr); received_native = *new_value; }; - native_lcm->subscribe("SuffixDrakeLcmTest_SUFFIX", std::move(handler)); + native_lcm.subscribe("SuffixDrakeLcmTest_SUFFIX", std::move(handler)); // Subscribe using Drake LCM (with the abbreviated channel name). lcmt_drake_signal received_drake{}; @@ -392,14 +394,14 @@ TEST_F(DrakeLcmTest, Suffix) { // Check that the native subscription gets it. LoopUntilDone(&received_native, 20 /* retries */, [&]() { Publish(dut_.get(), "SuffixDrakeLcmTest", message_); - native_lcm->handleTimeout(50 /* millis */); + native_lcm.handleTimeout(50 /* millis */); }); // Publish using the abbreviated channel name. // Check that the drake subscription gets it. LoopUntilDone(&received_drake, 20 /* retries */, [&]() { Publish(dut_.get(), "SuffixDrakeLcmTest", message_); - native_lcm->handleTimeout(50 /* millis */); + native_lcm.handleTimeout(50 /* millis */); }); } @@ -439,7 +441,7 @@ TEST_F(DrakeLcmTest, SuffixInSubscribeAllChannels) { // Confirm that SubscribeMultichannel ignores mismatched channel names. TEST_F(DrakeLcmTest, SubscribeMultiTest) { - ::lcm::LCM* const native_lcm = get_native(); + ::lcm::LCM native_lcm = get_native(); const std::string channel_name = "DrakeLcmTest.SubscribeMultiTest"; lcmt_drake_signal received{}; @@ -454,23 +456,13 @@ TEST_F(DrakeLcmTest, SubscribeMultiTest) { int total = 0; LoopUntilDone(&received, 20 /* retries */, [&]() { - native_lcm->publish("WRONG_" + channel_name, &message_); - native_lcm->publish(channel_name, &message_); + native_lcm.publish("WRONG_" + channel_name, &message_); + native_lcm.publish(channel_name, &message_); total += dut_->HandleSubscriptions(50 /* millis */); }); EXPECT_EQ(total, 1); } -#pragma GCC diagnostic push -#pragma GCC diagnostic ignored "-Wdeprecated-declarations" -TEST_F(DrakeLcmTest, DeprecatedGetter) { - ::lcm::LCM* const deprecated = dut_->get_lcm_instance(); - EXPECT_TRUE(deprecated != nullptr); - ::lcm::LCM* native = get_native(); - EXPECT_TRUE(native == deprecated); -} -#pragma GCC diagnostic pop - } // namespace } // namespace lcm } // namespace drake diff --git a/tools/install/libdrake/test/exported_symbols_test.py b/tools/install/libdrake/test/exported_symbols_test.py index 0a095cc1cf92..4f220f309a93 100644 --- a/tools/install/libdrake/test/exported_symbols_test.py +++ b/tools/install/libdrake/test/exported_symbols_test.py @@ -86,8 +86,6 @@ "slack_value", "sortOnOther", "wrapper", - # This fix is pending a deprecation removal (#20115) 2024-01-01. - "N3lcm", ]