Skip to content

Commit 7f41137

Browse files
authored
Updates to not use std::move in some places. (ros2#2353)
gcc 13.1.1 complains that these uses inhibit copy elision. Signed-off-by: Chris Lalancette <[email protected]>
1 parent 76e2b26 commit 7f41137

File tree

3 files changed

+4
-4
lines changed

3 files changed

+4
-4
lines changed

rclcpp/include/rclcpp/experimental/intra_process_manager.hpp

Lines changed: 2 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -467,7 +467,7 @@ class IntraProcessManager
467467
auto ptr = MessageAllocTraits::allocate(allocator, 1);
468468
MessageAllocTraits::construct(allocator, ptr, *message);
469469

470-
subscription->provide_intra_process_data(std::move(MessageUniquePtr(ptr, deleter)));
470+
subscription->provide_intra_process_data(MessageUniquePtr(ptr, deleter));
471471
}
472472

473473
continue;
@@ -510,7 +510,7 @@ class IntraProcessManager
510510
MessageAllocTraits::construct(allocator, ptr, *message);
511511

512512
ros_message_subscription->provide_intra_process_message(
513-
std::move(MessageUniquePtr(ptr, deleter)));
513+
MessageUniquePtr(ptr, deleter));
514514
}
515515
}
516516
}

rclcpp/include/rclcpp/publisher.hpp

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -390,7 +390,7 @@ class Publisher : public PublisherBase
390390
if (this->can_loan_messages()) {
391391
// we release the ownership from the rclpp::LoanedMessage instance
392392
// and let the middleware clean up the memory.
393-
this->do_loaned_message_publish(std::move(loaned_msg.release()));
393+
this->do_loaned_message_publish(loaned_msg.release());
394394
} else {
395395
// we don't release the ownership, let the middleware copy the ros message
396396
// and thus the destructor of rclcpp::LoanedMessage cleans up the memory.

rclcpp/test/rclcpp/test_publisher.cpp

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -482,7 +482,7 @@ class TestPublisherProtectedMethods : public rclcpp::Publisher<MessageT, Allocat
482482

483483
void publish_loaned_message(rclcpp::LoanedMessage<MessageT, AllocatorT> && loaned_msg)
484484
{
485-
this->do_loaned_message_publish(std::move(loaned_msg.release()));
485+
this->do_loaned_message_publish(loaned_msg.release());
486486
}
487487

488488
void call_default_incompatible_qos_callback(rclcpp::QOSOfferedIncompatibleQoSInfo & event) const

0 commit comments

Comments
 (0)