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

Commit

Permalink
Resolve conflicts
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 31, 2020
1 parent 65972ce commit c197e22
Show file tree
Hide file tree
Showing 4 changed files with 28 additions and 19 deletions.
5 changes: 5 additions & 0 deletions system_metrics_collector/CMakeLists.txt
Expand Up @@ -127,6 +127,11 @@ if(BUILD_TESTING)
test/system_metrics_collector/test_utilities.cpp)
target_link_libraries(test_utilities system_metrics_collector)
ament_target_dependencies(test_utilities rclcpp)

ament_add_gtest(test_subscriber_topic_statistics
test/topic_statistics_collector/test_subscriber_topic_statistics.cpp)
target_link_libraries(test_subscriber_topic_statistics system_metrics_collector)
ament_target_dependencies(test_subscriber_topic_statistics rcl rclcpp sensor_msgs)
endif()

# Install launch files
Expand Down
1 change: 1 addition & 0 deletions system_metrics_collector/package.xml
Expand Up @@ -27,6 +27,7 @@
<test_depend>ament_lint_common</test_depend>
<test_depend>class_loader</test_depend>
<test_depend>lifecycle_msgs</test_depend>
<test_depend>sensor_msgs</test_depend>

<!--Required for e2e test file-->
<test_depend>python3-retrying</test_depend>
Expand Down
Expand Up @@ -26,16 +26,22 @@
#include "rclcpp/rclcpp.hpp"
#include "rcpputils/asserts.hpp"

#include "received_message_age.hpp"
#include "received_message_period.hpp"
#include "libstatistics_collector/topic_statistics_collector/received_message_age.hpp"
#include "libstatistics_collector/topic_statistics_collector/received_message_period.hpp"
#include "libstatistics_collector/topic_statistics_collector/topic_statistics_collector.hpp"
#include "system_metrics_collector/constants.hpp"
#include "system_metrics_collector/metrics_message_publisher.hpp"
#include "topic_statistics_collector.hpp"


namespace topic_statistics_collector
{

using libstatistics_collector::topic_statistics_collector::TopicStatisticsCollector;
using libstatistics_collector::topic_statistics_collector::ReceivedMessageAgeCollector;
using libstatistics_collector::topic_statistics_collector::ReceivedMessagePeriodCollector;
namespace constants =
libstatistics_collector::topic_statistics_collector::topic_statistics_constants;

/**
* Build a positive integer range to use in parameter descriptors.
*
Expand Down Expand Up @@ -147,17 +153,17 @@ class SubscriberTopicStatisticsNode : public system_metrics_collector::MetricsMe
const auto collect_topic_desc = buildTopicParameterDescriptor(
"The topic to subscribe to, for calculating topic statistics.");
collect_topic_name_ = declare_parameter(
topic_statistics_constants::kCollectStatsTopicNameParam,
constants::kCollectStatsTopicNameParam,
std::string(),
collect_topic_desc);
validateStringParam(
topic_statistics_constants::kCollectStatsTopicNameParam,
constants::kCollectStatsTopicNameParam,
collect_topic_name_);

const auto publish_topic_desc = buildTopicParameterDescriptor(
"The topic to publish topic statistics to.");
publish_topic_name_ = declare_parameter(
topic_statistics_constants::kPublishStatsTopicNameParam,
constants::kPublishStatsTopicNameParam,
system_metrics_collector::collector_node_constants::kStatisticsTopicName,
publish_topic_desc);

Expand Down
Expand Up @@ -22,13 +22,16 @@
#include "lifecycle_msgs/msg/state.hpp"
#include "sensor_msgs/msg/imu.hpp"

#include "libstatistics_collector/topic_statistics_collector/constants.hpp"
#include "libstatistics_collector/topic_statistics_collector/topic_statistics_collector.hpp"
#include "system_metrics_collector/constants.hpp"
#include "topic_statistics_collector/constants.hpp"
#include "topic_statistics_collector/subscriber_topic_statistics.hpp"
#include "topic_statistics_collector/topic_statistics_collector.hpp"
#include "../system_metrics_collector/test_functions.hpp"

using lifecycle_msgs::msg::State;
using libstatistics_collector::moving_average_statistics::StatisticData;
namespace constants =
libstatistics_collector::topic_statistics_collector::topic_statistics_constants;

namespace
{
Expand Down Expand Up @@ -98,9 +101,9 @@ class TestSubscriberTopicStatisticsNode
*
* @return statistic data collected by all collectors
*/
std::vector<moving_average_statistics::StatisticData> GetCollectorData() const
std::vector<StatisticData> GetCollectorData() const
{
std::vector<moving_average_statistics::StatisticData> data;
std::vector<StatisticData> data;
for (const auto & collector : statistics_collectors_) {
data.push_back(collector->GetStatisticsResults());
}
Expand Down Expand Up @@ -185,9 +188,7 @@ class SubscriberTopicStatisticsNodeTestFixture : public testing::Test
options.append_parameter_override(
system_metrics_collector::collector_node_constants::kPublishPeriodParam,
kVeryLongPublishPeriod.count());
options.append_parameter_override(
topic_statistics_collector::topic_statistics_constants::kCollectStatsTopicNameParam,
kTestTopicName);
options.append_parameter_override(constants::kCollectStatsTopicNameParam, kTestTopicName);

imu_publisher_ = std::make_shared<ImuMessagePublisher>();
EXPECT_EQ(imu_publisher_->getSubscriptionCount(), 0);
Expand Down Expand Up @@ -363,9 +364,7 @@ TEST_F(RclcppFixture, TestConstructorPublishPeriodValidation) {

TEST_F(RclcppFixture, TestConstructorTopicNameValidation) {
rclcpp::NodeOptions options;
options.append_parameter_override(
topic_statistics_collector::topic_statistics_constants::kCollectStatsTopicNameParam,
std::string());
options.append_parameter_override(constants::kCollectStatsTopicNameParam, std::string());

ASSERT_THROW(
TestSubscriberTopicStatisticsNode("throw", options),
Expand All @@ -377,9 +376,7 @@ TEST_F(RclcppFixture, TestMetricsMessagePublisher) {
options.append_parameter_override(
system_metrics_collector::collector_node_constants::kPublishPeriodParam,
std::chrono::milliseconds{kTestDuration}.count());
options.append_parameter_override(
topic_statistics_collector::topic_statistics_constants::kCollectStatsTopicNameParam,
kTestTopicName);
options.append_parameter_override(constants::kCollectStatsTopicNameParam, kTestTopicName);

auto test_node = std::make_shared<TestSubscriberTopicStatisticsNode>(
"TestMetricsMessagePublisher",
Expand Down

0 comments on commit c197e22

Please sign in to comment.