Skip to content

Commit a3c3420

Browse files
committed
removed intra
Signed-off-by: CursedRock17 <[email protected]> Correct version of handle_message Signed-off-by: CursedRock17 <[email protected]>
1 parent 7071c3d commit a3c3420

File tree

1 file changed

+1
-12
lines changed

1 file changed

+1
-12
lines changed

rclcpp/include/rclcpp/subscription.hpp

Lines changed: 1 addition & 12 deletions
Original file line numberDiff line numberDiff line change
@@ -326,12 +326,6 @@ class Subscription : public SubscriptionBase
326326
const std::shared_ptr<rclcpp::SerializedMessage> & serialized_message,
327327
const rclcpp::MessageInfo & message_info) override
328328
{
329-
if (matches_any_intra_process_publishers(&message_info.get_rmw_message_info().publisher_gid)) {
330-
// In this case, the message will be delivered via intra process and
331-
// we should ignore this copy of the message.
332-
return;
333-
}
334-
335329
std::chrono::time_point<std::chrono::system_clock> now;
336330
if (subscription_topic_statistics_) {
337331
// get current time before executing callback to
@@ -341,15 +335,10 @@ class Subscription : public SubscriptionBase
341335

342336
any_callback_.dispatch(serialized_message, message_info);
343337

344-
ROSMessageType deserialized_message;
345-
auto serializer = rclcpp::Serialization<ROSMessageType>();
346-
serializer.deserialize_message(serialized_message.get(), &deserialized_message);
347-
348-
349338
if (subscription_topic_statistics_) {
350339
const auto nanos = std::chrono::time_point_cast<std::chrono::nanoseconds>(now);
351340
const auto time = rclcpp::Time(nanos.time_since_epoch().count());
352-
subscription_topic_statistics_->handle_message(deserialized_message, time);
341+
subscription_topic_statistics_->handle_message(message_info.get_rmw_message_info(), time);
353342
}
354343
}
355344

0 commit comments

Comments
 (0)