Skip to content

Commit

Permalink
Adds loopback support to DrakeMockLcm. (RobotLocomotion#4855)
Browse files Browse the repository at this point in the history
* Adds loopback support to DrakeMockLcm.

* Removed enum.
  • Loading branch information
Chien-Liang Fok authored Jan 23, 2017
1 parent 449be0b commit fb0d310
Show file tree
Hide file tree
Showing 3 changed files with 81 additions and 1 deletion.
6 changes: 5 additions & 1 deletion drake/lcm/drake_mock_lcm.cc
Original file line number Diff line number Diff line change
Expand Up @@ -33,6 +33,10 @@ void DrakeMockLcm::Publish(const std::string& channel, const void* data,

const uint8_t* bytes = reinterpret_cast<const uint8_t*>(data);
saved_message->data = std::vector<uint8_t>(&bytes[0], &bytes[data_size]);

if (enable_loop_back_) {
InduceSubscriberCallback(channel, data, data_size);
}
}

const std::vector<uint8_t>& DrakeMockLcm::get_last_published_message(
Expand Down Expand Up @@ -64,7 +68,7 @@ void DrakeMockLcm::Subscribe(const std::string& channel,
}

void DrakeMockLcm::InduceSubscriberCallback(const std::string& channel,
const void* data, int data_size) {
const void* data, int data_size) {
if (receive_thread_started_) {
if (subscriptions_.find(channel) == subscriptions_.end()) {
throw std::runtime_error(
Expand Down
8 changes: 8 additions & 0 deletions drake/lcm/drake_mock_lcm.h
Original file line number Diff line number Diff line change
Expand Up @@ -18,12 +18,19 @@ namespace lcm {
*/
class DrakeMockLcm : public DrakeLcmInterface {
public:
/**
* A constructor that creates a DrakeMockLcm where loopback is diabled, i.e.,
* a call to Publish() will not result in subscriber callback function being
* called. To enable loop-back behavior, call EnableLoopBack().
*/
DrakeMockLcm();

// Disable copy and assign.
DrakeMockLcm(const DrakeMockLcm&) = delete;
DrakeMockLcm& operator=(const DrakeMockLcm&) = delete;

void EnableLoopBack() { enable_loop_back_ = true; }

void StartReceiveThread() override;

void StopReceiveThread() override;
Expand Down Expand Up @@ -104,6 +111,7 @@ class DrakeMockLcm : public DrakeLcmInterface {
int data_size);

private:
bool enable_loop_back_{false};
bool receive_thread_started_{false};

struct LastPublishedMessage {
Expand Down
68 changes: 68 additions & 0 deletions drake/lcm/test/drake_mock_lcm_test.cc
Original file line number Diff line number Diff line change
Expand Up @@ -161,6 +161,74 @@ GTEST_TEST(DrakeMockLcmTest, SubscribeTest) {
EXPECT_EQ(message_bytes, received_bytes2);
}

// Tests DrakeMockLcm's ability to "publish" and "subscribe" to an LCM channel
// via a loopback.
GTEST_TEST(DrakeMockLcmTest, WithLoopbackTest) {
const string kChannelName =
"drake_mock_lcm_test_loopback_channel";

// Instantiates the Device Under Test (DUT). Note that loopback is enabled,
// which results in subscribers being notified when a message is published on
// the subscribed channel.
DrakeMockLcm dut;
dut.EnableLoopBack();

// Instantiates a message handler.
MockMessageHandler handler;

dut.StartReceiveThread();
dut.Subscribe(kChannelName, &handler);

// Defines a fake serialized message.
const int kMessageSize = 10;
vector<uint8_t> message_bytes(kMessageSize);

for (int i = 0; i < kMessageSize; ++i) {
message_bytes[i] = i;
}

dut.Publish(kChannelName, &message_bytes[0], kMessageSize);

// Verifies that the message was received via loopback.
EXPECT_EQ(kChannelName, handler.get_channel());
EXPECT_EQ(kMessageSize, handler.get_buffer_size());

const vector<uint8_t>& received_bytes = handler.get_buffer();
EXPECT_EQ(message_bytes, received_bytes);
}

// Tests that DrakeMockLcm will not loopback a message when loopback is
// disabled.
GTEST_TEST(DrakeMockLcmTest, WithoutLoopbackTest) {
const string kChannelName =
"drake_mock_lcm_test_without_loopback_channel";

// Instantiates the Device Under Test (DUT). Note that loopback is by default
// disabled, which results in subscribers not being notified when a message is
// published on the subscribed channel.
DrakeMockLcm dut;

// Instantiates a message handler.
MockMessageHandler handler;

dut.StartReceiveThread();
dut.Subscribe(kChannelName, &handler);

// Defines a fake serialized message.
const int kMessageSize = 10;
vector<uint8_t> message_bytes(kMessageSize);

for (int i = 0; i < kMessageSize; ++i) {
message_bytes[i] = i;
}

dut.Publish(kChannelName, &message_bytes[0], kMessageSize);

// Verifies that the message was not received via loopback.
EXPECT_NE(kChannelName, handler.get_channel());
EXPECT_NE(kMessageSize, handler.get_buffer_size());
}

} // namespace
} // namespace lcm
} // namespace drake

0 comments on commit fb0d310

Please sign in to comment.