From a3c3420970a2e891192dd694d41b795d3343bf08 Mon Sep 17 00:00:00 2001 From: CursedRock17 Date: Sat, 2 Sep 2023 20:37:40 -0400 Subject: [PATCH] removed intra Signed-off-by: CursedRock17 Correct version of handle_message Signed-off-by: CursedRock17 --- rclcpp/include/rclcpp/subscription.hpp | 13 +------------ 1 file changed, 1 insertion(+), 12 deletions(-) diff --git a/rclcpp/include/rclcpp/subscription.hpp b/rclcpp/include/rclcpp/subscription.hpp index 04e8263425..1b4a2952c4 100644 --- a/rclcpp/include/rclcpp/subscription.hpp +++ b/rclcpp/include/rclcpp/subscription.hpp @@ -326,12 +326,6 @@ class Subscription : public SubscriptionBase const std::shared_ptr & serialized_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; - } - std::chrono::time_point now; if (subscription_topic_statistics_) { // get current time before executing callback to @@ -341,15 +335,10 @@ class Subscription : public SubscriptionBase any_callback_.dispatch(serialized_message, message_info); - ROSMessageType deserialized_message; - auto serializer = rclcpp::Serialization(); - serializer.deserialize_message(serialized_message.get(), &deserialized_message); - - if (subscription_topic_statistics_) { const auto nanos = std::chrono::time_point_cast(now); const auto time = rclcpp::Time(nanos.time_since_epoch().count()); - subscription_topic_statistics_->handle_message(deserialized_message, time); + subscription_topic_statistics_->handle_message(message_info.get_rmw_message_info(), time); } }