diff --git a/rclcpp/include/rclcpp/loaned_message.hpp b/rclcpp/include/rclcpp/loaned_message.hpp index 3b94d86ae0..530ddc5024 100644 --- a/rclcpp/include/rclcpp/loaned_message.hpp +++ b/rclcpp/include/rclcpp/loaned_message.hpp @@ -179,20 +179,6 @@ class LoanedMessage return *message_; } - /// Release ownership of the ROS message instance. - /** - * A call to `release()` will unmanage the memory for the ROS message. - * That means that the destructor of this class will not free the memory on scope exit. - * - * \return Raw pointer to the message instance. - */ - MessageT * release() - { - auto msg = message_; - message_ = nullptr; - return msg; - } - protected: const rclcpp::PublisherBase & pub_; diff --git a/rclcpp/test/rclcpp/test_loaned_message.cpp b/rclcpp/test/rclcpp/test_loaned_message.cpp index 20a2e3b1ee..f5c6afc4df 100644 --- a/rclcpp/test/rclcpp/test_loaned_message.cpp +++ b/rclcpp/test/rclcpp/test_loaned_message.cpp @@ -60,26 +60,3 @@ TEST_F(TestLoanedMessage, loan_from_pub) { SUCCEED(); } - -TEST_F(TestLoanedMessage, release) { - auto node = std::make_shared("loaned_message_test_node"); - auto pub = node->create_publisher("loaned_message_test_topic", 1); - - MessageT * msg = nullptr; - { - auto loaned_msg = pub->borrow_loaned_message(); - ASSERT_TRUE(loaned_msg.is_valid()); - loaned_msg.get().float64_value = 42.0f; - ASSERT_EQ(42.0f, loaned_msg.get().float64_value); - msg = loaned_msg.release(); - // call destructor implicitly. - // destructor not allowed to free memory because of not having ownership - // of the data after a call to release. - } - - ASSERT_EQ(42.0f, msg->float64_value); - - msg->~MessageT(); - pub->get_allocator()->deallocate(msg, 1); - SUCCEED(); -}