Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Add API to use message_info instead unserialized message #170

Merged
merged 14 commits into from
Oct 11, 2023
Merged
8 changes: 5 additions & 3 deletions CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -32,6 +32,7 @@ find_package(ament_cmake_ros REQUIRED)
find_package(builtin_interfaces REQUIRED)
find_package(rcl REQUIRED)
find_package(rcpputils REQUIRED)
find_package(rmw REQUIRED)
find_package(statistics_msgs REQUIRED)

add_library(${PROJECT_NAME}
Expand All @@ -49,6 +50,7 @@ target_include_directories(${PROJECT_NAME} PUBLIC
ament_target_dependencies(${PROJECT_NAME}
"builtin_interfaces"
"rcl"
"rmw"
CursedRock17 marked this conversation as resolved.
Show resolved Hide resolved
"rcpputils"
"statistics_msgs"
)
Expand All @@ -67,7 +69,7 @@ ament_export_libraries(${PROJECT_NAME})
# Export modern CMake targets
ament_export_targets(${PROJECT_NAME})

ament_export_dependencies("builtin_interfaces" "rcl" "rcpputils" "rosidl_default_runtime" "statistics_msgs")
ament_export_dependencies("builtin_interfaces" "rcl" "rcpputils" "rmw" "rosidl_default_runtime" "statistics_msgs")

if(BUILD_TESTING)
find_package(ament_lint_auto REQUIRED)
Expand All @@ -91,12 +93,12 @@ if(BUILD_TESTING)
ament_add_gtest(test_received_message_period
test/topic_statistics_collector/test_received_message_period.cpp)
target_link_libraries(test_received_message_period ${PROJECT_NAME})
ament_target_dependencies(test_received_message_period "rcl" "rcpputils")
ament_target_dependencies(test_received_message_period "rcl" "rmw" "rcpputils")

ament_add_gtest(test_received_message_age
test/topic_statistics_collector/test_received_message_age.cpp)
target_link_libraries(test_received_message_age ${PROJECT_NAME})
ament_target_dependencies(test_received_message_age "rcl" "rcpputils")
ament_target_dependencies(test_received_message_age "rcl" "rmw" "rcpputils")

rosidl_generate_interfaces(libstatistics_collector_test_msgs
"test/msg/DummyMessage.msg"
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -28,6 +28,8 @@
#include "builtin_interfaces/msg/time.hpp"
#include "rcl/time.h"

#include "rmw/types.h"

namespace libstatistics_collector
{
namespace topic_statistics_collector
Expand Down Expand Up @@ -84,13 +86,22 @@ struct TimeStamp<M, typename std::enable_if<HasHeader<M>::value>::type>
}
};

/**
* Primary specialization class template until deprecated templated class is phased out
*/
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.
*
* @tparam T the message type to receive from the subscriber / listener
*/
template<typename T>
class ReceivedMessageAgeCollector : public TopicStatisticsCollector<T>
class ReceivedMessageAgeCollector<
T, std::enable_if_t<!std::is_same<T, rmw_message_info_t>::value>>
: public TopicStatisticsCollector<T>
{
public:
ReceivedMessageAgeCollector() = default;
Expand All @@ -103,6 +114,8 @@ class ReceivedMessageAgeCollector : public TopicStatisticsCollector<T>
* @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"
MichaelOrlov marked this conversation as resolved.
Show resolved Hide resolved
"with an untyped ReceivedMessageAgeCollector<>")]]
void OnMessageReceived(
const T & received_message,
const rcl_time_point_value_t now_nanoseconds) override
Expand Down Expand Up @@ -152,6 +165,72 @@ class ReceivedMessageAgeCollector : public TopicStatisticsCollector<T>
}
};

/**
* Class used to measure the received messsage age from a ROS2 subscriber.
*/
template<>
class ReceivedMessageAgeCollector<
rmw_message_info_t,
std::enable_if_t<std::is_same<rmw_message_info_t, rmw_message_info_t>::value>>
: public TopicStatisticsCollector<>
{
public:
ReceivedMessageAgeCollector() = default;

virtual ~ReceivedMessageAgeCollector() = default;

/**
* Handle a new incoming message. Calculate message age if a valid Header is present.
*
CursedRock17 marked this conversation as resolved.
Show resolved Hide resolved
* @param received_message the message to calculate age of.
CursedRock17 marked this conversation as resolved.
Show resolved Hide resolved
* @param now_nanoseconds time the message was received in nanoseconds
*/
void OnMessageReceived(
const rmw_message_info_t & received_message,
CursedRock17 marked this conversation as resolved.
Show resolved Hide resolved
const rcl_time_point_value_t now_nanoseconds) override
{
// only compare if non-zero
if (received_message.source_timestamp && now_nanoseconds) {
const std::chrono::nanoseconds age_nanos{now_nanoseconds -
received_message.source_timestamp};
const auto age_millis = std::chrono::duration<double, std::milli>(age_nanos);

collector::Collector::AcceptData(static_cast<double>(age_millis.count()));
} // else no valid time to compute age
}

/**
* Return message age metric name
*
* @return a string representing message age metric name
*/
std::string GetMetricName() const override
{
return topic_statistics_constants::kMsgAgeStatName;
}

/**
* Return messge age metric unit
*
* @return a string representing messager age metric unit
*/
std::string GetMetricUnit() const override
{
return topic_statistics_constants::kMillisecondUnitName;
}

protected:
bool SetupStart() override
{
return true;
}

bool SetupStop() override
{
return true;
}
};

} // namespace topic_statistics_collector
} // namespace libstatistics_collector

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -24,21 +24,32 @@

#include "rcl/time.h"

#include "rmw/types.h"

namespace libstatistics_collector
{
namespace topic_statistics_collector
{

constexpr const int64_t kUninitializedTime{0};

/**
CursedRock17 marked this conversation as resolved.
Show resolved Hide resolved
* Primary specialization class template until deprecated templated class is phased out
*/
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
* 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 : public TopicStatisticsCollector<T>
class ReceivedMessagePeriodCollector<
T, std::enable_if_t<!std::is_same<T, rmw_message_info_t>::value>>
: public TopicStatisticsCollector<T>
{
public:
/**
Expand All @@ -59,6 +70,8 @@ class ReceivedMessagePeriodCollector : public TopicStatisticsCollector<T>
* @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 @@ -129,6 +142,100 @@ class ReceivedMessagePeriodCollector : public TopicStatisticsCollector<T>
mutable std::mutex mutex_;
};

template<>
class ReceivedMessagePeriodCollector<rmw_message_info_t,
std::enable_if_t<std::is_same<rmw_message_info_t, rmw_message_info_t>::value>>
: public TopicStatisticsCollector<>
{
public:
/**
* Construct a ReceivedMessagePeriodCollector object.
*
*/
ReceivedMessagePeriodCollector()
{
ResetTimeLastMessageReceived();
}

virtual ~ReceivedMessagePeriodCollector() = default;

/**
* Handle a message received and measure its received period. This member is thread safe and acquires
* a lock to prevent race conditions when setting the time_last_message_received_ member.
*
* @param received_message
* @param now_nanoseconds time the message was received in nanoseconds
*/
void OnMessageReceived(
const rmw_message_info_t & received_message,
const rcl_time_point_value_t now_nanoseconds)
override RCPPUTILS_TSA_REQUIRES(mutex_)
{
std::unique_lock<std::mutex> ulock{mutex_};

if (time_last_message_received_ == kUninitializedTime) {
time_last_message_received_ = now_nanoseconds;
} else {
const std::chrono::nanoseconds nanos{now_nanoseconds - time_last_message_received_};
const auto period = std::chrono::duration<double, std::milli>(nanos);
time_last_message_received_ = now_nanoseconds;
collector::Collector::AcceptData(static_cast<double>(period.count()));
}
}

/**
* Return message period metric name
*
* @return a string representing message period metric name
*/
std::string GetMetricName() const override
{
return topic_statistics_constants::kMsgPeriodStatName;
}

/**
* Return message period metric unit
*
* @return a string representing message period metric unit
*/
std::string GetMetricUnit() const override
{
return topic_statistics_constants::kMillisecondUnitName;
}

protected:
/**
* Reset the time_last_message_received_ member.
* @return true
*/
bool SetupStart() override
{
ResetTimeLastMessageReceived();
return true;
}

bool SetupStop() override
{
return true;
}

private:
/**
* Resets time_last_message_received_ to the expected uninitialized_time_.
*/
void ResetTimeLastMessageReceived()
{
time_last_message_received_ = kUninitializedTime;
}

/**
* Default uninitialized time.
*/
rcl_time_point_value_t time_last_message_received_ RCPPUTILS_TSA_GUARDED_BY(mutex_) =
kUninitializedTime;
mutable std::mutex mutex_;
};

} // namespace topic_statistics_collector
} // namespace libstatistics_collector

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -21,20 +21,31 @@

#include "rcl/time.h"

#include "rmw/types.h"

#include "libstatistics_collector/collector/collector.hpp"

namespace libstatistics_collector
{
namespace topic_statistics_collector
{

/**
* Primary specialization class template until deprecated templated class is phased out
*/
template<typename T = rmw_message_info_t, typename Enable = void>
class TopicStatisticsCollector : public collector::Collector
{};

/**
* Interface to collect and perform measurements for ROS2 topic statistics.
*
* @tparam T the ROS2 message type to collect
*/
template<typename T>
class TopicStatisticsCollector : public collector::Collector
class TopicStatisticsCollector<
T, std::enable_if_t<!std::is_same<T, rmw_message_info_t>::value>>
: public collector::Collector
{
public:
TopicStatisticsCollector() = default;
Expand All @@ -49,11 +60,39 @@ class TopicStatisticsCollector : public collector::Collector
* 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;
};

/**
* Interface to collect and perform measurements for ROS2 topic statistics.
*/
template<>
class TopicStatisticsCollector<rmw_message_info_t,
std::enable_if_t<std::is_same<rmw_message_info_t, rmw_message_info_t>::value>>
: public collector::Collector
{
public:
TopicStatisticsCollector() = default;

virtual ~TopicStatisticsCollector() = default;

/**
* 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.
*/
virtual void OnMessageReceived(
const rmw_message_info_t & received_message,
const rcl_time_point_value_t now_nanoseconds) = 0;
};

} // namespace topic_statistics_collector
} // namespace libstatistics_collector

Expand Down
1 change: 1 addition & 0 deletions package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -12,6 +12,7 @@
<depend>builtin_interfaces</depend>
<depend>rcl</depend>
<depend>rcpputils</depend>
<depend>rmw</depend>
<depend>statistics_msgs</depend>

<test_depend>ament_cmake_gtest</test_depend>
Expand Down
Loading
Loading