Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

[lcm] Deprecate direct access to the native LCM library #20115

Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
2 changes: 1 addition & 1 deletion lcm/drake_lcm.cc
Original file line number Diff line number Diff line change
Expand Up @@ -105,7 +105,7 @@ std::string DrakeLcm::get_lcm_url() const {
return impl_->lcm_url_;
}

::lcm::LCM* DrakeLcm::get_lcm_instance() {
::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_);
Expand Down
12 changes: 10 additions & 2 deletions lcm/drake_lcm.h
Original file line number Diff line number Diff line change
Expand Up @@ -6,14 +6,15 @@
#include <string_view>

#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_lcm_instance() -- an advanced function that is rarely used.
// DrakeLcm::get_native() -- an unit-test-only private function.
class LCM;
} // namespace lcm
#endif
Expand Down Expand Up @@ -53,12 +54,15 @@ 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();
::lcm::LCM* get_lcm_instance() { return get_native(); }

void Publish(const std::string&, const void*, int,
std::optional<double>) override;
Expand All @@ -72,8 +76,12 @@ class DrakeLcm : public DrakeLcmInterface {
int HandleSubscriptions(int) override;

private:
friend class DrakeLcmTester;

void OnHandleSubscriptionsError(const std::string&) override;

::lcm::LCM* get_native();

class Impl;
std::unique_ptr<Impl> impl_;
};
Expand Down
35 changes: 28 additions & 7 deletions lcm/test/drake_lcm_test.cc
Original file line number Diff line number Diff line change
Expand Up @@ -13,6 +13,15 @@

namespace drake {
namespace lcm {
// Provides friend access to the underlying LCM object.
class DrakeLcmTester {
public:
DrakeLcmTester() = delete;
static ::lcm::LCM* get_native(DrakeLcm* dut) {
DRAKE_DEMAND(dut != nullptr);
return dut->get_native();
}
};
namespace {

// A udpm URL that is not the default. We'll transmit here in our tests.
Expand Down Expand Up @@ -50,6 +59,8 @@ class DrakeLcmTest : public ::testing::Test {
EXPECT_TRUE(message_was_received);
}

::lcm::LCM* get_native() { return DrakeLcmTester::get_native(dut_.get()); }

// The device under test.
std::unique_ptr<DrakeLcm> dut_ = std::make_unique<DrakeLcm>();

Expand Down Expand Up @@ -88,7 +99,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 = dut_->get_lcm_instance();
::lcm::LCM* const native_lcm = get_native();
const std::string channel_name = "DrakeLcmTest.PublishTest";

lcmt_drake_signal received{};
Expand All @@ -109,7 +120,7 @@ TEST_F(DrakeLcmTest, PublishTest) {
// 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 = dut_->get_lcm_instance();
::lcm::LCM* const native_lcm = get_native();
const std::string channel_name = "DrakeLcmTest.SubscribeTest";

lcmt_drake_signal received{};
Expand All @@ -129,7 +140,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 = dut_->get_lcm_instance();
::lcm::LCM* const native_lcm = get_native();
const std::string channel_name = "DrakeLcmTest.SubscribeTest2";

lcmt_drake_signal received{};
Expand All @@ -150,7 +161,7 @@ TEST_F(DrakeLcmTest, SubscribeTest2) {

// Repeat SubscribeTest for SubscribeAllChannels.
TEST_F(DrakeLcmTest, SubscribeAllTest) {
::lcm::LCM* const native_lcm = dut_->get_lcm_instance();
::lcm::LCM* const native_lcm = get_native();
const std::string channel_name = "DrakeLcmTest.SubscribeAllTest";

lcmt_drake_signal received{};
Expand All @@ -172,7 +183,7 @@ TEST_F(DrakeLcmTest, SubscribeAllTest) {

// Repeat SubscribeTest2 for SubscribeAllChannels.
TEST_F(DrakeLcmTest, SubscribeAllTest2) {
::lcm::LCM* const native_lcm = dut_->get_lcm_instance();
::lcm::LCM* const native_lcm = get_native();
const std::string channel_name = "DrakeLcmTest.SubscribeAllTest2";

lcmt_drake_signal received{};
Expand Down Expand Up @@ -352,7 +363,7 @@ TEST_F(DrakeLcmTest, Suffix) {
DrakeLcmParams params;
params.channel_suffix = "_SUFFIX";
dut_ = std::make_unique<DrakeLcm>(params);
::lcm::LCM* const native_lcm = dut_->get_lcm_instance();
::lcm::LCM* const native_lcm = get_native();

// Subscribe using native LCM (with the fully-qualified channel name).
lcmt_drake_signal received_native{};
Expand Down Expand Up @@ -422,7 +433,7 @@ TEST_F(DrakeLcmTest, SuffixInSubscribeAllChannels) {

// Confirm that SubscribeMultichannel ignores mismatched channel names.
TEST_F(DrakeLcmTest, SubscribeMultiTest) {
::lcm::LCM* const native_lcm = dut_->get_lcm_instance();
::lcm::LCM* const native_lcm = get_native();
const std::string channel_name = "DrakeLcmTest.SubscribeMultiTest";

lcmt_drake_signal received{};
Expand All @@ -444,6 +455,16 @@ TEST_F(DrakeLcmTest, SubscribeMultiTest) {
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
71 changes: 11 additions & 60 deletions lcm/test/drake_lcm_thread_test.cc
Original file line number Diff line number Diff line change
Expand Up @@ -27,16 +27,15 @@ class MessageMailbox {
public:
DRAKE_NO_COPY_NO_MOVE_NO_ASSIGN(MessageMailbox)

MessageMailbox() = default;

lcmt_drake_signal GetMessage() const {
lcmt_drake_signal result{};
std::lock_guard<std::mutex> lock(mutex_);
result = message_;
return result;
}

protected:
MessageMailbox() = default;

void SetMessage(const lcmt_drake_signal& new_value) {
std::lock_guard<std::mutex> lock(mutex_);
message_ = new_value;
Expand All @@ -47,46 +46,6 @@ class MessageMailbox {
lcmt_drake_signal message_{};
};

// Subscribes to LCM without any DrakeLcmInterface sugar or mocks.
class NativeMailbox final : public MessageMailbox {
public:
DRAKE_NO_COPY_NO_MOVE_NO_ASSIGN(NativeMailbox)

// A constructor that adds the LCM message subscription.
NativeMailbox(const std::string& channel_name, ::lcm::LCM* lcm) {
lcm->subscribe(channel_name, &NativeMailbox::Handle, this);
}

private:
void Handle(const ::lcm::ReceiveBuffer*, const std::string&,
const lcmt_drake_signal* message) {
DRAKE_DEMAND(message != nullptr);
SetMessage(*message);
}
};

// Subscribes to LCM using DrakeLcm::Subscribe.
class DutMailbox final : public MessageMailbox {
public:
DRAKE_NO_COPY_NO_MOVE_NO_ASSIGN(DutMailbox)

DutMailbox(const std::string& channel, DrakeLcm* dut) {
auto subscription =
dut->Subscribe(channel, [this](const void* data, int size) {
this->Handle(data, size);
});
// By default, deleting the subscription should not unsubscribe.
subscription.reset();
}

private:
void Handle(const void* data, int size) {
lcmt_drake_signal decoded{};
decoded.decode(data, 0, size);
SetMessage(decoded);
}
};

// Test fixture.
class DrakeLcmThreadTest : public ::testing::Test {
protected:
Expand Down Expand Up @@ -135,25 +94,17 @@ class DrakeLcmThreadTest : public ::testing::Test {
lcmt_drake_signal message_{};
};

// Tests DrakeLcm's ability to publish an LCM message.
// We subscribe using the native LCM APIs.
TEST_F(DrakeLcmThreadTest, PublishTest) {
::lcm::LCM* const native_lcm = dut_.get_lcm_instance();
const std::string channel_name = "DrakeLcmThreadTest.PublishTest";
NativeMailbox mailbox(channel_name, native_lcm);
LoopUntilDone(mailbox, [&]() {
Publish(&dut_, channel_name, message_);
// Tests DrakeLcm's ability to pub/sub LCM messages using threads.
TEST_F(DrakeLcmThreadTest, PubSubTest) {
const std::string channel_name = "DrakeLcmThreadTest.PubSubTest";
MessageMailbox mailbox;
dut_.Subscribe(channel_name, [&mailbox](const void* data, int size) {
lcmt_drake_signal decoded{};
decoded.decode(data, 0, size);
mailbox.SetMessage(decoded);
});
}

// Tests DrakeLcm's ability to subscribe to an LCM message.
// We publish using the native LCM APIs.
TEST_F(DrakeLcmThreadTest, SubscribeTest) {
::lcm::LCM* const native_lcm = dut_.get_lcm_instance();
const std::string channel_name = "DrakeLcmThreadTest.SubscribeTest";
DutMailbox mailbox(channel_name, &dut_);
LoopUntilDone(mailbox, [&]() {
native_lcm->publish(channel_name, &message_);
Publish(&dut_, channel_name, message_);
});
}

Expand Down