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 received message age metric to topic statistics #1080

Merged
merged 15 commits into from
Apr 24, 2020
15 changes: 14 additions & 1 deletion rclcpp/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -12,6 +12,7 @@ find_package(rcpputils REQUIRED)
find_package(rcutils REQUIRED)
find_package(rmw REQUIRED)
find_package(rosgraph_msgs REQUIRED)
find_package(rosidl_default_generators REQUIRED)
find_package(rosidl_runtime_cpp REQUIRED)
find_package(rosidl_typesupport_c REQUIRED)
find_package(rosidl_typesupport_cpp REQUIRED)
Expand Down Expand Up @@ -223,6 +224,14 @@ if(BUILD_TESTING)

add_definitions(-DTEST_RESOURCES_DIRECTORY="${CMAKE_CURRENT_BINARY_DIR}/test/resources")

rosidl_generate_interfaces(${PROJECT_NAME}_test_msgs
test/msg/Header.msg
test/msg/MessageWithHeader.msg
DEPENDENCIES builtin_interfaces
LIBRARY_NAME ${PROJECT_NAME}
prajakta-gokhale marked this conversation as resolved.
Show resolved Hide resolved
SKIP_INSTALL
)

ament_add_gtest(test_client test/test_client.cpp)
if(TARGET test_client)
ament_target_dependencies(test_client
Expand Down Expand Up @@ -610,9 +619,12 @@ if(BUILD_TESTING)
target_link_libraries(test_wait_set ${PROJECT_NAME})
endif()

ament_add_gtest(test_subscription_topic_statistics test/topic_statistics/test_subscription_topic_statistics.cpp)
ament_add_gtest(test_subscription_topic_statistics test/topic_statistics/test_subscription_topic_statistics.cpp
APPEND_LIBRARY_DIRS "${append_library_dirs}"
)
if(TARGET test_subscription_topic_statistics)
ament_target_dependencies(test_subscription_topic_statistics
"builtin_interfaces"
"libstatistics_collector"
"rcl_interfaces"
"rcutils"
Expand All @@ -621,6 +633,7 @@ if(BUILD_TESTING)
"rosidl_typesupport_cpp"
"statistics_msgs"
"test_msgs")
rosidl_target_interfaces(test_subscription_topic_statistics ${PROJECT_NAME}_test_msgs "rosidl_typesupport_cpp")
target_link_libraries(test_subscription_topic_statistics ${PROJECT_NAME})
endif()

Expand Down
4 changes: 2 additions & 2 deletions rclcpp/include/rclcpp/subscription.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -271,8 +271,8 @@ class Subscription : public SubscriptionBase

if (subscription_topic_statistics_) {
const auto nanos = std::chrono::time_point_cast<std::chrono::nanoseconds>(
std::chrono::steady_clock::now());
const auto time = rclcpp::Time(nanos.time_since_epoch().count(), RCL_STEADY_TIME);
std::chrono::system_clock::now());
Copy link
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

IIUC, this change is because we're assuming that the timestamp in message headers is using system time, right?

What happens if a node is using simulation time (ie. ROS_TIME)?

Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

That is correct. There is also no way to specify a message's time source when we were assuming one would use the std_msgs/Header (I brought this up with @wjwwood and @tfoote during the message review).

Copy link
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Okay, so it sounds like a known limitation of topic statistics for the moment; not compatible with simulation.

Copy link
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

The type in std_msgs::msg::Header can be ROS time... Both ROS Time and System time share an epoch, the unix epoch. It's only when you want to use a different Epoch or behavior for the clock that the stamp in header is insufficient, e.g. like steady time or TAI time.

So in this situation I don't understand why you cannot use ROS Time...

Copy link
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

I guess we could ROS time, and assume the incoming messages are using the same epoch as this node.

At the end of the day we can't know if the time in the header will have the same epoch as the time from this node, right? Since one of them may being use simulation time and the other not.

Copy link
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Simulated time uses the same epoch as system time, at least that's my understanding. If you are simulating time and then set the time to 1 (as in 1 nanosecond) then it's 1 nanosecond after jan 1 1970.

At least that's how I interrpret it:

Perhaps it should be clarified, but I think ROS time and system time should be usable interchangeably.

const auto time = rclcpp::Time(nanos.time_since_epoch().count());
subscription_topic_statistics_->handle_message(*typed_message, time);
}
}
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -23,6 +23,7 @@
#include "libstatistics_collector/collector/generate_statistics_message.hpp"
#include "libstatistics_collector/moving_average_statistics/types.hpp"
#include "libstatistics_collector/topic_statistics_collector/constants.hpp"
#include "libstatistics_collector/topic_statistics_collector/received_message_age.hpp"
#include "libstatistics_collector/topic_statistics_collector/received_message_period.hpp"

#include "rcl/time.h"
Expand Down Expand Up @@ -56,6 +57,9 @@ class SubscriptionTopicStatistics
using TopicStatsCollector =
libstatistics_collector::topic_statistics_collector::TopicStatisticsCollector<
CallbackMessageT>;
using ReceivedMessageAge =
libstatistics_collector::topic_statistics_collector::ReceivedMessageAgeCollector<
CallbackMessageT>;
using ReceivedMessagePeriod =
libstatistics_collector::topic_statistics_collector::ReceivedMessagePeriodCollector<
CallbackMessageT>;
Expand Down Expand Up @@ -173,6 +177,10 @@ class SubscriptionTopicStatistics
*/
void bring_up()
{
auto received_message_age = std::make_unique<ReceivedMessageAge>();
received_message_age->Start();
subscriber_statistics_collectors_.emplace_back(std::move(received_message_age));

auto received_message_period = std::make_unique<ReceivedMessagePeriod>();
received_message_period->Start();
{
Expand Down
1 change: 1 addition & 0 deletions rclcpp/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -37,6 +37,7 @@
<test_depend>ament_lint_common</test_depend>
<test_depend>rmw</test_depend>
<test_depend>rmw_implementation_cmake</test_depend>
<test_depend>rosidl_default_generators</test_depend>
<test_depend>test_msgs</test_depend>

<export>
Expand Down
3 changes: 3 additions & 0 deletions rclcpp/test/msg/Header.msg
Original file line number Diff line number Diff line change
@@ -0,0 +1,3 @@
# Simple Header message with a timestamp field.

builtin_interfaces/Time stamp
3 changes: 3 additions & 0 deletions rclcpp/test/msg/MessageWithHeader.msg
Original file line number Diff line number Diff line change
@@ -0,0 +1,3 @@
# Message containing a simple Header field.

Header header
Loading