Skip to content
This repository has been archived by the owner on Jun 10, 2021. It is now read-only.

Commit

Permalink
Fix unit test and try to increase coverage
Browse files Browse the repository at this point in the history
Signed-off-by: Prajakta Gokhale <prajaktg@amazon.com>
  • Loading branch information
Prajakta Gokhale committed Mar 20, 2020
1 parent e57a4d1 commit 2b8b9ba
Showing 1 changed file with 24 additions and 7 deletions.
Expand Up @@ -22,7 +22,6 @@
#include "lifecycle_msgs/msg/state.hpp"
#include "sensor_msgs/msg/imu.hpp"

#include "../system_metrics_collector/test_constants.hpp"
#include "system_metrics_collector/collector.hpp"
#include "system_metrics_collector/constants.hpp"
#include "topic_statistics_collector/constants.hpp"
Expand Down Expand Up @@ -121,6 +120,11 @@ class ImuMessagePublisher : public rclcpp::Node
publisher_->publish(*msg);
}

uint64_t getSubscriptionCount() const
{
return publisher_->get_subscription_count();
}

private:
typename rclcpp::Publisher<sensor_msgs::msg::Imu>::SharedPtr publisher_;
};
Expand All @@ -139,13 +143,18 @@ class SubscriberTopicStatisticsNodeTestFixture : public testing::Test
options.append_parameter_override(kPublishPeriodParam, kDontPublishDuringTest.count());
options.append_parameter_override(kCollectStatsTopicName, kTestTopicName);

imu_publisher_ = std::make_shared<ImuMessagePublisher>();
EXPECT_EQ(imu_publisher_->getSubscriptionCount(), 0);

test_periodic_publisher_ = std::make_shared<TestSubscriberTopicStatisticsNode>(
kTestNodeName, options);

const auto collectors = test_periodic_publisher_->GetCollectors();
ASSERT_FALSE(collectors.empty());

moving_average_statistics::StatisticData data;
for (const auto & collector : collectors) {
auto data = collector->GetStatisticsResults();
data = collector->GetStatisticsResults();
ASSERT_TRUE(std::isnan(data.average));
ASSERT_TRUE(std::isnan(data.min));
ASSERT_TRUE(std::isnan(data.max));
Expand All @@ -161,6 +170,7 @@ class SubscriberTopicStatisticsNodeTestFixture : public testing::Test
EXPECT_FALSE(test_periodic_publisher_->IsPublisherActivated());

test_periodic_publisher_.reset();
imu_publisher_.reset();
rclcpp::shutdown();
}

Expand All @@ -170,6 +180,7 @@ class SubscriberTopicStatisticsNodeTestFixture : public testing::Test
// itself
static constexpr std::chrono::milliseconds kDontPublishDuringTest = 2 * kTestDuration;
std::shared_ptr<TestSubscriberTopicStatisticsNode> test_periodic_publisher_;
std::shared_ptr<ImuMessagePublisher> imu_publisher_;
};

/**
Expand Down Expand Up @@ -228,20 +239,26 @@ TEST_F(SubscriberTopicStatisticsNodeTestFixture, TestStart) {
ASSERT_TRUE(test_periodic_publisher_->IsPublisherActivated());
}

TEST_F(SubscriberTopicStatisticsNodeTestFixture, TestSubscriptionCallbackAndPublish) {
TEST_F(SubscriberTopicStatisticsNodeTestFixture, TestSubscriptionCallback) {
test_periodic_publisher_->configure();
test_periodic_publisher_->activate();

ImuMessagePublisher publisher;
const auto msg = GetImuMessageWithHeader();
for (int i = 0; i < kTimesCallbackCalled; ++i) {
publisher.publish(msg);
imu_publisher_->publish(msg);
}

std::promise<bool> empty_promise;
std::shared_future<bool> dummy_future = empty_promise.get_future();

rclcpp::executors::SingleThreadedExecutor ex;
ex.add_node(test_periodic_publisher_->get_node_base_interface());
ex.spin_until_future_complete(dummy_future, kTestDuration);

moving_average_statistics::StatisticData data;
for (const auto & collector : test_periodic_publisher_->GetCollectors()) {
data = collector->GetStatisticsResults();
ASSERT_EQ(kTimesCallbackCalled, data.sample_count);
ASSERT_GT(data.sample_count, 0);
ASSERT_FALSE(std::isnan(data.average));
ASSERT_FALSE(std::isnan(data.min));
ASSERT_FALSE(std::isnan(data.max));
Expand All @@ -250,7 +267,7 @@ TEST_F(SubscriberTopicStatisticsNodeTestFixture, TestSubscriptionCallbackAndPubl

int times_published = test_periodic_publisher_->GetNumPublished();
ASSERT_EQ(
test_constants::kTestDuration.count() / kDontPublishDuringTest.count(), times_published);
kTestDuration.count() / kDontPublishDuringTest.count(), times_published);
}

TEST_F(SubscriberTopicStatisticsNodeTestFixture, TestStop) {
Expand Down

0 comments on commit 2b8b9ba

Please sign in to comment.