Skip to content

Commit

Permalink
Change naming style to match rclcpp
Browse files Browse the repository at this point in the history
Signed-off-by: Devin Bonnie <dbbonnie@amazon.com>
  • Loading branch information
dabonnie committed Apr 13, 2020
1 parent 1953a32 commit 8eaba16
Show file tree
Hide file tree
Showing 2 changed files with 15 additions and 17 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -39,11 +39,9 @@ namespace
{
/// Return the current nanoseconds (count) since epoch.
/**
* For now, use hard coded time instead of a node's clock (to support sim time and playback)
* due to node clock lifecycle issues.
* \return the current nanoseconds (count) since epoch
*/
int64_t GetCurrentNanosecondsSinceEpoch()
int64_t get_current_nanoseconds_since_epoch()
{
const auto now = std::chrono::system_clock::now();
return std::chrono::duration_cast<std::chrono::nanoseconds>(now.time_since_epoch()).count();
Expand Down Expand Up @@ -101,27 +99,27 @@ class SubscriberTopicStatistics

auto callback = [this]()
{
this->PublishMessage();
this->publish_message();
};

publisher_timer_ = node.create_wall_timer(publishing_period, callback);

node_name_ = node.get_name();

BringUp();
bring_up();
}

virtual ~SubscriberTopicStatistics()
{
TearDown();
tear_down();
}

/// Handle a message received by the subscription to collect statistics.
/**
* \param received_message the message received by the subscription
* \param now_nanoseconds current time in nanoseconds
*/
virtual void OnMessageReceived(
virtual void handle_message(
const CallbackMessageT & received_message,
const rcl_time_point_value_t now_nanoseconds) const
{
Expand All @@ -136,7 +134,7 @@ class SubscriberTopicStatistics
/**
* \return a vector of all the collected data
*/
std::vector<StatisticData> GetCurrentCollectorData() const
std::vector<StatisticData> get_current_collector_data() const
{
std::vector<StatisticData> data;
for (const auto & collector : subscriber_statistics_collectors_) {
Expand All @@ -147,17 +145,17 @@ class SubscriberTopicStatistics

private:
/// Construct and start all collectors and set window_start_.
void BringUp()
void bring_up()
{
auto received_message_period = std::make_unique<ReceivedMessagePeriod>();
received_message_period->Start();
subscriber_statistics_collectors_.emplace_back(std::move(received_message_period));

window_start_ = rclcpp::Time(GetCurrentNanosecondsSinceEpoch());
window_start_ = rclcpp::Time(get_current_nanoseconds_since_epoch());
}

/// Stop all collectors, clear measurements, stop publishing timer, and reset publisher.
void TearDown()
void tear_down()
{
for (auto & collector : subscriber_statistics_collectors_) {
collector->Stop();
Expand All @@ -174,9 +172,9 @@ class SubscriberTopicStatistics
}

/// Publish a populated MetricsStatisticsMessage
virtual void PublishMessage()
virtual void publish_message()
{
rclcpp::Time window_end{GetCurrentNanosecondsSinceEpoch()};
rclcpp::Time window_end{get_current_nanoseconds_since_epoch()};

for (auto & collector : subscriber_statistics_collectors_) {
const auto collected_stats = collector->GetStatisticsResults();
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -54,7 +54,7 @@ class EmptySubscriber : public rclcpp::Node
: Node(name)
{
auto callback = [this](Empty::UniquePtr msg) {
this->ReceiveMessage(*msg);
this->receive_message(*msg);
};
subscription_ = create_subscription<Empty,
std::function<void(Empty::UniquePtr)>>(
Expand All @@ -64,7 +64,7 @@ class EmptySubscriber : public rclcpp::Node
}

private:
void ReceiveMessage(const Empty &) const
void receive_message(const Empty &) const
{
}

Expand Down Expand Up @@ -93,14 +93,14 @@ class TestSubscriberTopicStatisticsFixture : public ::testing::Test
std::shared_ptr<EmptySubscriber> empty_subscriber;
};

TEST_F(TestSubscriberTopicStatisticsFixture, TestManualConstruction)
TEST_F(TestSubscriberTopicStatisticsFixture, test_manual_construction)
{
// construct the instance
auto sub_topic_stats = std::make_unique<SubscriberTopicStatistics<Empty>>(
*empty_subscriber);

// expect no data has been collected / no samples received
for (const auto & data : sub_topic_stats->GetCurrentCollectorData()) {
for (const auto & data : sub_topic_stats->get_current_collector_data()) {
EXPECT_TRUE(std::isnan(data.average));
EXPECT_TRUE(std::isnan(data.min));
EXPECT_TRUE(std::isnan(data.max));
Expand Down

0 comments on commit 8eaba16

Please sign in to comment.