Skip to content

Commit

Permalink
Remove the release method of LoadedMessage and a related test case
Browse files Browse the repository at this point in the history
Signed-off-by: Chen Lihui <Lihui.Chen@sony.com>
  • Loading branch information
Chen Lihui authored and Chen Lihui committed Sep 23, 2020
1 parent bc22d8e commit b982525
Show file tree
Hide file tree
Showing 2 changed files with 0 additions and 37 deletions.
14 changes: 0 additions & 14 deletions rclcpp/include/rclcpp/loaned_message.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -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_;

Expand Down
23 changes: 0 additions & 23 deletions rclcpp/test/rclcpp/test_loaned_message.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -60,26 +60,3 @@ TEST_F(TestLoanedMessage, loan_from_pub) {

SUCCEED();
}

TEST_F(TestLoanedMessage, release) {
auto node = std::make_shared<rclcpp::Node>("loaned_message_test_node");
auto pub = node->create_publisher<MessageT>("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();
}

0 comments on commit b982525

Please sign in to comment.