Skip to content

Commit

Permalink
Add statistics for handle_loaned_message (#1927) (#1932)
Browse files Browse the repository at this point in the history
* Add statistics for handle_loaned_message

Signed-off-by: Barry Xu <barry.xu@sony.com>
(cherry picked from commit 5c68830)

Co-authored-by: Barry Xu <barry.xu@sony.com>
  • Loading branch information
mergify[bot] and Barry-Xu-2018 committed Jun 9, 2022
1 parent c24e485 commit cf2a278
Showing 1 changed file with 20 additions and 0 deletions.
20 changes: 20 additions & 0 deletions rclcpp/include/rclcpp/subscription.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -363,11 +363,31 @@ class Subscription : public SubscriptionBase
void * loaned_message,
const rclcpp::MessageInfo & message_info) override
{
if (matches_any_intra_process_publishers(&message_info.get_rmw_message_info().publisher_gid)) {
// In this case, the message will be delivered via intra process and
// we should ignore this copy of the message.
return;
}

auto typed_message = static_cast<ROSMessageType *>(loaned_message);
// message is loaned, so we have to make sure that the deleter does not deallocate the message
auto sptr = std::shared_ptr<ROSMessageType>(
typed_message, [](ROSMessageType * msg) {(void) msg;});

std::chrono::time_point<std::chrono::system_clock> now;
if (subscription_topic_statistics_) {
// get current time before executing callback to
// exclude callback duration from topic statistics result.
now = std::chrono::system_clock::now();
}

any_callback_.dispatch(sptr, message_info);

if (subscription_topic_statistics_) {
const auto nanos = std::chrono::time_point_cast<std::chrono::nanoseconds>(now);
const auto time = rclcpp::Time(nanos.time_since_epoch().count());
subscription_topic_statistics_->handle_message(*typed_message, time);
}
}

/// Return the borrowed message.
Expand Down

0 comments on commit cf2a278

Please sign in to comment.