Skip to content
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
6 changes: 6 additions & 0 deletions rclcpp/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -535,6 +535,12 @@ if(BUILD_TESTING)
target_link_libraries(test_wait_set ${PROJECT_NAME})
endif()

ament_add_gtest(test_subscription_options test/test_subscription_options.cpp)
if(TARGET test_subscription_options)
ament_target_dependencies(test_subscription_options "rcl")
target_link_libraries(test_subscription_options ${PROJECT_NAME})
endif()

# Install test resources
install(
DIRECTORY test/resources
Expand Down
20 changes: 20 additions & 0 deletions rclcpp/include/rclcpp/subscription_options.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -15,6 +15,7 @@
#ifndef RCLCPP__SUBSCRIPTION_OPTIONS_HPP_
#define RCLCPP__SUBSCRIPTION_OPTIONS_HPP_

#include <chrono>
#include <memory>
#include <string>
#include <vector>
Expand Down Expand Up @@ -54,6 +55,24 @@ struct SubscriptionOptionsBase
/// Optional RMW implementation specific payload to be used during creation of the subscription.
std::shared_ptr<rclcpp::detail::RMWImplementationSpecificSubscriptionPayload>
rmw_implementation_payload = nullptr;

// Options to configure topic statistics collector in the subscription.
struct TopicStatisticsOptions
{
// Represent the state of topic statistics collector.
enum class TopicStatisticsState {ENABLED, DISABLED};

// Enable and disable topic statistics calculation and publication. Defaults to disabled.
TopicStatisticsState state = TopicStatisticsState::DISABLED;

// Topic to which topic statistics get published when enabled. Defaults to /statistics.
std::string publish_topic = "/statistics";

// Topic statistics publication period in ms. Defaults to one minute.
std::chrono::milliseconds publish_period{std::chrono::seconds(1)};
};

TopicStatisticsOptions topic_stats_options;
};

/// Structure containing optional configuration for Subscriptions.
Expand Down Expand Up @@ -104,6 +123,7 @@ struct SubscriptionOptionsWithAllocator : public SubscriptionOptionsBase
};

using SubscriptionOptions = SubscriptionOptionsWithAllocator<std::allocator<void>>;
using TopicStatisticsState = SubscriptionOptionsBase::TopicStatisticsOptions::TopicStatisticsState;

} // namespace rclcpp

Expand Down
44 changes: 44 additions & 0 deletions rclcpp/test/test_subscription_options.cpp
Original file line number Diff line number Diff line change
@@ -0,0 +1,44 @@
// Copyright 2020 Amazon.com, Inc. or its affiliates. All Rights Reserved.
//
// Licensed under the Apache License, Version 2.0 (the "License");
// you may not use this file except in compliance with the License.
// You may obtain a copy of the License at
//
// http://www.apache.org/licenses/LICENSE-2.0
//
// Unless required by applicable law or agreed to in writing, software
// distributed under the License is distributed on an "AS IS" BASIS,
// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
// See the License for the specific language governing permissions and
// limitations under the License.

#include <gtest/gtest.h>

#include <chrono>
#include <string>
#include <vector>

#include "rclcpp/subscription_options.hpp"

using namespace std::chrono_literals;

namespace
{
constexpr const char defaultPublishTopic[] = "/statistics";
}

TEST(TestSubscriptionOptions, topic_statistics_options) {
auto options = rclcpp::SubscriptionOptions();

EXPECT_EQ(options.topic_stats_options.state, rclcpp::TopicStatisticsState::DISABLED);
EXPECT_EQ(options.topic_stats_options.publish_topic, defaultPublishTopic);
EXPECT_EQ(options.topic_stats_options.publish_period, 1s);

options.topic_stats_options.state = rclcpp::TopicStatisticsState::ENABLED;
options.topic_stats_options.publish_topic = "topic_statistics";
options.topic_stats_options.publish_period = 5min;

EXPECT_EQ(options.topic_stats_options.state, rclcpp::TopicStatisticsState::ENABLED);
EXPECT_EQ(options.topic_stats_options.publish_topic, "topic_statistics");
EXPECT_EQ(options.topic_stats_options.publish_period, 5min);
}