Skip to content

Commit

Permalink
drake_lcm: Add IsReceiveThreadRunning()
Browse files Browse the repository at this point in the history
  • Loading branch information
EricCousineau-TRI committed Mar 9, 2018
1 parent ea66e59 commit e762170
Show file tree
Hide file tree
Showing 8 changed files with 42 additions and 3 deletions.
5 changes: 4 additions & 1 deletion lcm/drake_lcm.cc
Original file line number Diff line number Diff line change
Expand Up @@ -39,7 +39,10 @@ void DrakeLcm::StartReceiveThread() {
}

void DrakeLcm::StopReceiveThread() {
if (receive_thread_ != nullptr) receive_thread_->Stop();
if (receive_thread_ != nullptr) {
receive_thread_->Stop();
receive_thread_.reset();
}
}

::lcm::LCM* DrakeLcm::get_lcm_instance() { return &lcm_; }
Expand Down
4 changes: 4 additions & 0 deletions lcm/drake_lcm.h
Original file line number Diff line number Diff line change
Expand Up @@ -32,6 +32,10 @@ class DrakeLcm : public DrakeLcmInterface {

void StopReceiveThread() override;

bool IsReceiveThreadRunning() const override {
return receive_thread_ != nullptr;
}

/**
* An accessor to the real LCM instance encapsulated by this object. The
* returned pointer is guaranteed to be valid for the duration of this
Expand Down
5 changes: 5 additions & 0 deletions lcm/drake_lcm_interface.h
Original file line number Diff line number Diff line change
Expand Up @@ -39,6 +39,11 @@ class DrakeLcmInterface {
*/
virtual void StopReceiveThread() = 0;

/**
* Indicates that the receiving thread is running.
*/
virtual bool IsReceiveThreadRunning() const = 0;

/**
* Publishes an LCM message on channel @p channel.
*
Expand Down
13 changes: 11 additions & 2 deletions lcm/drake_lcm_log.h
Original file line number Diff line number Diff line change
@@ -1,5 +1,6 @@
#pragma once

#include <atomic>
#include <map>
#include <memory>
#include <mutex>
Expand Down Expand Up @@ -116,8 +117,15 @@ class DrakeLcmLog : public DrakeLcmInterface {
return static_cast<uint64_t>(sec * 1e6);
}

void StartReceiveThread() override {}
void StopReceiveThread() override {}
void StartReceiveThread() override {
receive_thread_started_ = true;
}
void StopReceiveThread() override {
receive_thread_started_ = false;
}
bool IsReceiveThreadRunning() const override {
return receive_thread_started_;
}

private:
const bool is_write_;
Expand All @@ -129,6 +137,7 @@ class DrakeLcmLog : public DrakeLcmInterface {
mutable std::mutex mutex_;
std::unique_ptr<::lcm::LogFile> log_;
const ::lcm::LogEvent* next_event_{nullptr};
std::atomic<bool> receive_thread_started_{false};
};

} // namespace lcm
Expand Down
4 changes: 4 additions & 0 deletions lcm/drake_mock_lcm.h
Original file line number Diff line number Diff line change
Expand Up @@ -40,6 +40,10 @@ class DrakeMockLcm : public DrakeLcmInterface {

void StopReceiveThread() override;

bool IsReceiveThreadRunning() const override {
return receive_thread_started_;
}

void Publish(const std::string& channel, const void* data,
int data_size, double time_sec = 0) override;

Expand Down
6 changes: 6 additions & 0 deletions lcm/test/drake_lcm_log_test.cc
Original file line number Diff line number Diff line change
Expand Up @@ -37,6 +37,12 @@ GTEST_TEST(LcmLogTest, LcmLogTestSaveAndRead) {
auto w_log = std::make_unique<DrakeLcmLog>("test.log", true);
const std::string channel_name("test_channel");

EXPECT_FALSE(w_log->IsReceiveThreadRunning());
w_log->StartReceiveThread();
EXPECT_TRUE(w_log->IsReceiveThreadRunning());
w_log->StopReceiveThread();
EXPECT_FALSE(w_log->IsReceiveThreadRunning());

drake::lcmt_drake_signal msg;
msg.dim = 1;
msg.val.push_back(0.1);
Expand Down
4 changes: 4 additions & 0 deletions lcm/test/drake_lcm_test.cc
Original file line number Diff line number Diff line change
Expand Up @@ -102,7 +102,10 @@ TEST_F(DrakeLcmTest, PublishTest) {
// order of construction, this ensures the LCM receive thread stops before any
// resources it uses are destroyed. If the Lcm receive thread is stopped after
// the resources it relies on are destroyed, a segmentation fault may occur.

EXPECT_FALSE(dut.IsReceiveThreadRunning());
dut.StartReceiveThread();
EXPECT_TRUE(dut.IsReceiveThreadRunning());

// Records whether the receiver received an LCM message published by the DUT.
bool done = false;
Expand Down Expand Up @@ -130,6 +133,7 @@ TEST_F(DrakeLcmTest, PublishTest) {

dut.StopReceiveThread();
EXPECT_TRUE(done);
EXPECT_FALSE(dut.IsReceiveThreadRunning());
}

// Handles received LCM messages.
Expand Down
4 changes: 4 additions & 0 deletions lcm/test/drake_mock_lcm_test.cc
Original file line number Diff line number Diff line change
Expand Up @@ -29,7 +29,9 @@ GTEST_TEST(DrakeMockLcmTest, PublishTest) {
// Instantiates the Device Under Test (DUT).
DrakeMockLcm dut;

EXPECT_FALSE(dut.IsReceiveThreadRunning());
dut.StartReceiveThread();
EXPECT_TRUE(dut.IsReceiveThreadRunning());
dut.Publish(channel_name, &message_bytes[0], message_size);

// Verifies that the message was "published".
Expand All @@ -38,6 +40,8 @@ GTEST_TEST(DrakeMockLcmTest, PublishTest) {

EXPECT_EQ(message_size, static_cast<int>(published_message_bytes.size()));
EXPECT_EQ(message_bytes, published_message_bytes);
dut.StopReceiveThread();
EXPECT_FALSE(dut.IsReceiveThreadRunning());
}

// Tests DrakeMockLcm::DecodeLastPublishedMessageAs() using an lcmt_drake_signal
Expand Down

0 comments on commit e762170

Please sign in to comment.