Skip to content

Commit 206e0fd

Browse files
authored
Add statistics for handle_loaned_message (backport #1927) (#1933)
* Add statistics for handle_loaned_message (#1927) Signed-off-by: Barry Xu <barry.xu@sony.com> (cherry picked from commit 5c68830) * Fix merge conflicts (#1938) Signed-off-by: Barry Xu <barry.xu@sony.com>
1 parent 4fc3791 commit 206e0fd

File tree

1 file changed

+20
-0
lines changed

1 file changed

+20
-0
lines changed

rclcpp/include/rclcpp/subscription.hpp

+20
Original file line numberDiff line numberDiff line change
@@ -295,11 +295,31 @@ class Subscription : public SubscriptionBase
295295
void * loaned_message,
296296
const rclcpp::MessageInfo & message_info) override
297297
{
298+
if (matches_any_intra_process_publishers(&message_info.get_rmw_message_info().publisher_gid)) {
299+
// In this case, the message will be delivered via intra process and
300+
// we should ignore this copy of the message.
301+
return;
302+
}
303+
298304
auto typed_message = static_cast<CallbackMessageT *>(loaned_message);
299305
// message is loaned, so we have to make sure that the deleter does not deallocate the message
300306
auto sptr = std::shared_ptr<CallbackMessageT>(
301307
typed_message, [](CallbackMessageT * msg) {(void) msg;});
308+
309+
std::chrono::time_point<std::chrono::system_clock> now;
310+
if (subscription_topic_statistics_) {
311+
// get current time before executing callback to
312+
// exclude callback duration from topic statistics result.
313+
now = std::chrono::system_clock::now();
314+
}
315+
302316
any_callback_.dispatch(sptr, message_info);
317+
318+
if (subscription_topic_statistics_) {
319+
const auto nanos = std::chrono::time_point_cast<std::chrono::nanoseconds>(now);
320+
const auto time = rclcpp::Time(nanos.time_since_epoch().count());
321+
subscription_topic_statistics_->handle_message(*typed_message, time);
322+
}
303323
}
304324

305325
/// Return the borrowed message.

0 commit comments

Comments
 (0)