Skip to content

Commit

Permalink
Merge pull request #1 from ros-tooling/morlov/deprecate_on_class_leve…
Browse files Browse the repository at this point in the history
…l_in_topic_statistics_collector

Deprecate partially templated specifications on class level in topic statistics collector
  • Loading branch information
CursedRock17 authored Oct 11, 2023
2 parents b974592 + 47b6b06 commit 596f9f1
Show file tree
Hide file tree
Showing 5 changed files with 56 additions and 47 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -88,22 +88,31 @@ struct TimeStamp<M, typename std::enable_if<HasHeader<M>::value>::type>

/**
* Primary specialization class template until deprecated templated class is phased out
* @warning Don't use templated version of the ReceivedMessageAgeCollector, use
* libstatistics_collector::ReceivedMessageAgeCollector alias with rmw_message_info_t
* parameter in the OnMessageReceived callback
*/
template<typename T = rmw_message_info_t, typename Enable = void>
class ReceivedMessageAgeCollector : public TopicStatisticsCollector<T>
{};

/**
* Class used to measure the received messsage, tparam T, age from a ROS2 subscriber.
* Class used to measure the received message, tparam T, age from a ROS2 subscriber.
*
* @tparam T the message type to receive from the subscriber / listener
*/
template<typename T>
class ReceivedMessageAgeCollector<
T, std::enable_if_t<!std::is_same<T, rmw_message_info_t>::value>>
class
[[deprecated("Don't use templated version of the ReceivedMessageAgeCollector, use"
"libstatistics_collector::ReceivedMessageAgeCollector alias instead")]]
ReceivedMessageAgeCollector<T, std::enable_if_t<!std::is_same<T, rmw_message_info_t>::value>>
: public TopicStatisticsCollector<T>
{
public:
/**
* Construct a ReceivedMessageAgeCollector object.
*
*/
ReceivedMessageAgeCollector() = default;

virtual ~ReceivedMessageAgeCollector() = default;
Expand All @@ -114,8 +123,6 @@ class ReceivedMessageAgeCollector<
* @param received_message the message to calculate age of.
* @param now_nanoseconds time the message was received in nanoseconds
*/
[[deprecated("Don't use ReceivedMessageAgeCollector with type T, use rmw_message_info_t"
"with an untyped ReceivedMessageAgeCollector<>")]]
void OnMessageReceived(
const T & received_message,
const rcl_time_point_value_t now_nanoseconds) override
Expand Down Expand Up @@ -144,7 +151,7 @@ class ReceivedMessageAgeCollector<
}

/**
* Return messge age metric unit
* Return message age metric unit
*
* @return a string representing messager age metric unit
*/
Expand All @@ -166,7 +173,7 @@ class ReceivedMessageAgeCollector<
};

/**
* Class used to measure the received messsage age from a ROS2 subscriber.
* Class used to measure the received message age from a ROS2 subscriber.
*/
template<>
class ReceivedMessageAgeCollector<
Expand All @@ -177,7 +184,7 @@ class ReceivedMessageAgeCollector<
public:
ReceivedMessageAgeCollector() = default;

virtual ~ReceivedMessageAgeCollector() = default;
~ReceivedMessageAgeCollector() override = default;

/**
* Handle a new incoming message. Calculate message age if timestamps in message info are valid.
Expand Down Expand Up @@ -210,9 +217,9 @@ class ReceivedMessageAgeCollector<
}

/**
* Return messge age metric unit
* Return message age metric unit
*
* @return a string representing messager age metric unit
* @return a string representing message age metric unit
*/
std::string GetMetricUnit() const override
{
Expand All @@ -232,6 +239,9 @@ class ReceivedMessageAgeCollector<
};

} // namespace topic_statistics_collector

using ReceivedMessageAgeCollector = topic_statistics_collector::ReceivedMessageAgeCollector<>;

} // namespace libstatistics_collector

#endif // LIBSTATISTICS_COLLECTOR__TOPIC_STATISTICS_COLLECTOR__RECEIVED_MESSAGE_AGE_HPP_
Original file line number Diff line number Diff line change
Expand Up @@ -35,20 +35,25 @@ constexpr const int64_t kUninitializedTime{0};

/**
* Primary specialization class template until deprecated templated class is phased out
* @warning Don't use templated version of the ReceivedMessagePeriodCollector, use
* libstatistics_collector::ReceivedMessagePeriodCollector alias with rmw_message_info_t
* parameter in the OnMessageReceived callback
*/
template<typename T = rmw_message_info_t, typename Enable = void>
class ReceivedMessagePeriodCollector : public TopicStatisticsCollector<T>
{};

/**
* Class used to measure the received messsage, tparam T, period from a ROS2 subscriber. This class
* Class used to measure the received message, tparam T, period from a ROS2 subscriber. This class
* is thread safe and acquires a mutex when the member OnMessageReceived is executed.
*
* @tparam T the message type to receive from the subscriber / listener
*/
template<typename T>
class ReceivedMessagePeriodCollector<
T, std::enable_if_t<!std::is_same<T, rmw_message_info_t>::value>>
class
[[deprecated("Don't use templated version of the ReceivedMessagePeriodCollector, use"
"libstatistics_collector::ReceivedMessagePeriodCollector alias instead")]]
ReceivedMessagePeriodCollector<T, std::enable_if_t<!std::is_same<T, rmw_message_info_t>::value>>
: public TopicStatisticsCollector<T>
{
public:
Expand All @@ -70,8 +75,6 @@ class ReceivedMessagePeriodCollector<
* @param received_message
* @param now_nanoseconds time the message was received in nanoseconds
*/
[[deprecated("Don't use ReceivedMessagePeriodCollector with type T, use rmw_message_info_t"
"with an untyped ReceivedMessagePeriodCollector<>")]]
void OnMessageReceived(const T & received_message, const rcl_time_point_value_t now_nanoseconds)
override RCPPUTILS_TSA_REQUIRES(mutex_)
{
Expand Down Expand Up @@ -143,7 +146,8 @@ class ReceivedMessagePeriodCollector<
};

template<>
class ReceivedMessagePeriodCollector<rmw_message_info_t,
class ReceivedMessagePeriodCollector<
rmw_message_info_t,
std::enable_if_t<std::is_same<rmw_message_info_t, rmw_message_info_t>::value>>
: public TopicStatisticsCollector<>
{
Expand All @@ -157,7 +161,7 @@ class ReceivedMessagePeriodCollector<rmw_message_info_t,
ResetTimeLastMessageReceived();
}

virtual ~ReceivedMessagePeriodCollector() = default;
~ReceivedMessagePeriodCollector() override = default;

/**
* Handle a message received and measure its received period. This member is thread safe and acquires
Expand Down Expand Up @@ -237,6 +241,9 @@ class ReceivedMessagePeriodCollector<rmw_message_info_t,
};

} // namespace topic_statistics_collector

using ReceivedMessagePeriodCollector = topic_statistics_collector::ReceivedMessagePeriodCollector<>;

} // namespace libstatistics_collector

#endif // LIBSTATISTICS_COLLECTOR__TOPIC_STATISTICS_COLLECTOR__RECEIVED_MESSAGE_PERIOD_HPP_
Original file line number Diff line number Diff line change
Expand Up @@ -32,6 +32,9 @@ namespace topic_statistics_collector

/**
* Primary specialization class template until deprecated templated class is phased out
* @warning Don't use templated version of the TopicStatisticsCollector, use
* libstatistics_collector::TopicStatisticsCollector alias with rmw_message_info_t parameter in
* the OnMessageReceived callback
*/
template<typename T = rmw_message_info_t, typename Enable = void>
class TopicStatisticsCollector : public collector::Collector
Expand All @@ -43,8 +46,10 @@ class TopicStatisticsCollector : public collector::Collector
* @tparam T the ROS2 message type to collect
*/
template<typename T>
class TopicStatisticsCollector<
T, std::enable_if_t<!std::is_same<T, rmw_message_info_t>::value>>
class
[[deprecated("Don't use templated version of the TopicStatisticsCollector, use"
"libstatistics_collector::TopicStatisticsCollector alias instead")]]
TopicStatisticsCollector<T, std::enable_if_t<!std::is_same<T, rmw_message_info_t>::value>>
: public collector::Collector
{
public:
Expand All @@ -60,8 +65,6 @@ class TopicStatisticsCollector<
* following 1). the time provided is strictly monotonic 2). the time provided uses the same source
* as time obtained from the message header.
*/
[[deprecated("Don't use TopicStatisticsCollector with type T, use rmw_message_info_t"
"with an untyped TopicStatisticsCollector<>")]]
virtual void OnMessageReceived(
const T & received_message,
const rcl_time_point_value_t now_nanoseconds) = 0;
Expand All @@ -84,16 +87,20 @@ class TopicStatisticsCollector<rmw_message_info_t,
* Handle receiving a single message of type rmw_message_info_t.
*
* @param received_message rmw_message_info_t the ROS2 message type to collect
* @param now_nanoseconds nanoseconds the time the message was received. Any metrics using this time assumes the
* following 1). the time provided is strictly monotonic 2). the time provided uses the same source
* as time obtained from the message header.
* @param now_nanoseconds nanoseconds the time the message was received.
* Any metrics using this time assumes the following:
* 1). the time provided is strictly monotonic
* 2). the time provided uses the same source as time obtained from the message header.
*/
virtual void OnMessageReceived(
const rmw_message_info_t & received_message,
const rcl_time_point_value_t now_nanoseconds) = 0;
};

} // namespace topic_statistics_collector

using TopicStatisticsCollector = topic_statistics_collector::TopicStatisticsCollector<>;

} // namespace libstatistics_collector

#endif // LIBSTATISTICS_COLLECTOR__TOPIC_STATISTICS_COLLECTOR__TOPIC_STATISTICS_COLLECTOR_HPP_
15 changes: 4 additions & 11 deletions test/topic_statistics_collector/test_received_message_age.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -17,19 +17,12 @@
#include <chrono>
#include <string>

#include "libstatistics_collector/msg/dummy_message.hpp"
#include "libstatistics_collector/msg/dummy_custom_header_message.hpp"
#include "libstatistics_collector/topic_statistics_collector/constants.hpp"
#include "libstatistics_collector/topic_statistics_collector/received_message_age.hpp"

#include "rcl/time.h"

#include "rmw/types.h"

namespace
{
using ReceivedMessageAgeCollector = libstatistics_collector::
topic_statistics_collector::ReceivedMessageAgeCollector<>;
using ReceivedMessageAgeCollector = libstatistics_collector::ReceivedMessageAgeCollector;

constexpr const std::chrono::seconds kDefaultDurationSeconds{1};
constexpr const double kExpectedAverageMilliseconds{2000.0};
Expand Down Expand Up @@ -115,8 +108,8 @@ TEST(ReceivedMessageAgeTest, TestAgeMeasurement) {
}

TEST(ReceivedMessageAgeTest, TestGetStatNameAndUnit) {
ReceivedMessageAgeCollector test_untyped_collector{};
ReceivedMessageAgeCollector test_collector{};

EXPECT_FALSE(test_untyped_collector.GetMetricName().empty());
EXPECT_FALSE(test_untyped_collector.GetMetricUnit().empty());
EXPECT_FALSE(test_collector.GetMetricName().empty());
EXPECT_FALSE(test_collector.GetMetricUnit().empty());
}
16 changes: 4 additions & 12 deletions test/topic_statistics_collector/test_received_message_period.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -16,24 +16,17 @@
#include <gtest/gtest.h>

#include <chrono>
#include <string>
#include <thread>

#include "libstatistics_collector/moving_average_statistics/types.hpp"
#include "libstatistics_collector/topic_statistics_collector/constants.hpp"
#include "libstatistics_collector/topic_statistics_collector/received_message_period.hpp"

#include "rcl/time.h"

#include "rmw/types.h"

namespace
{
using ReceivedMessagePeriodCollector =
libstatistics_collector::topic_statistics_collector::ReceivedMessagePeriodCollector<>;
using ReceivedMessagePeriodCollector = libstatistics_collector::ReceivedMessagePeriodCollector;

constexpr const std::chrono::seconds kDefaultDurationSeconds{1};
constexpr const int kDefaultMessage{42};
constexpr const double kExpectedAverageMilliseconds{1000.0};
constexpr const double kExpectedMinMilliseconds{1000.0};
constexpr const double kExpectedMaxMilliseconds{1000.0};
Expand Down Expand Up @@ -68,10 +61,9 @@ TEST(ReceivedMessagePeriodTest, TestPeriodMeasurement) {
EXPECT_EQ(kExpectedStandardDeviation, stats.standard_deviation);
}


TEST(ReceivedMessagePeriodTest, TestGetStatNameAndUnit) {
ReceivedMessagePeriodCollector untyped_test{};
ReceivedMessagePeriodCollector test{};

EXPECT_FALSE(untyped_test.GetMetricName().empty());
EXPECT_FALSE(untyped_test.GetMetricUnit().empty());
EXPECT_FALSE(test.GetMetricName().empty());
EXPECT_FALSE(test.GetMetricUnit().empty());
}

0 comments on commit 596f9f1

Please sign in to comment.