rename return functions for loaned messages (#896)
* fix up documentation for zero copy api Signed-off-by: Karsten Knese <karsten@openrobotics.org> * rename loan_message to borrow_loaned_message Signed-off-by: Karsten Knese <karsten@openrobotics.org> * use return_loaned_message_from Signed-off-by: Karsten Knese <karsten@openrobotics.org>
This commit is contained in:
parent
3de5337376
commit
a6e3412bb0
5 changed files with 12 additions and 12 deletions
|
@ -137,7 +137,7 @@ public:
|
||||||
if (pub_.can_loan_messages()) {
|
if (pub_.can_loan_messages()) {
|
||||||
// return allocated memory to the middleware
|
// return allocated memory to the middleware
|
||||||
auto ret =
|
auto ret =
|
||||||
rcl_return_loaned_message(pub_.get_publisher_handle(), message_);
|
rcl_return_loaned_message_from_publisher(pub_.get_publisher_handle(), message_);
|
||||||
if (ret != RCL_RET_OK) {
|
if (ret != RCL_RET_OK) {
|
||||||
RCLCPP_ERROR(
|
RCLCPP_ERROR(
|
||||||
error_logger, "rcl_deallocate_loaned_message failed: %s", rcl_get_error_string().str);
|
error_logger, "rcl_deallocate_loaned_message failed: %s", rcl_get_error_string().str);
|
||||||
|
|
|
@ -129,7 +129,7 @@ public:
|
||||||
virtual ~Publisher()
|
virtual ~Publisher()
|
||||||
{}
|
{}
|
||||||
|
|
||||||
/// Loan memory for a ROS message from the middleware
|
/// Borrow a loaned ROS message from the middleware.
|
||||||
/**
|
/**
|
||||||
* If the middleware is capable of loaning memory for a ROS message instance,
|
* If the middleware is capable of loaning memory for a ROS message instance,
|
||||||
* the loaned message will be directly allocated in the middleware.
|
* the loaned message will be directly allocated in the middleware.
|
||||||
|
@ -137,14 +137,15 @@ public:
|
||||||
*
|
*
|
||||||
* With a call to \sa `publish` the LoanedMessage instance is being returned to the middleware
|
* With a call to \sa `publish` the LoanedMessage instance is being returned to the middleware
|
||||||
* or free'd accordingly to the allocator.
|
* or free'd accordingly to the allocator.
|
||||||
* If the message is not being published but processed differently, the message has to be
|
* If the message is not being published but processed differently, the destructor of this
|
||||||
* returned by calling \sa `return_loaned_message`.
|
* class will either return the message to the middleware or deallocate it via the internal
|
||||||
|
* allocator.
|
||||||
* \sa rclcpp::LoanedMessage for details of the LoanedMessage class.
|
* \sa rclcpp::LoanedMessage for details of the LoanedMessage class.
|
||||||
*
|
*
|
||||||
* \return LoanedMessage containing memory for a ROS message of type MessageT
|
* \return LoanedMessage containing memory for a ROS message of type MessageT
|
||||||
*/
|
*/
|
||||||
rclcpp::LoanedMessage<MessageT, AllocatorT>
|
rclcpp::LoanedMessage<MessageT, AllocatorT>
|
||||||
loan_message()
|
borrow_loaned_message()
|
||||||
{
|
{
|
||||||
return rclcpp::LoanedMessage<MessageT, AllocatorT>(this, this->get_allocator());
|
return rclcpp::LoanedMessage<MessageT, AllocatorT>(this, this->get_allocator());
|
||||||
}
|
}
|
||||||
|
@ -201,9 +202,9 @@ public:
|
||||||
return this->do_serialized_publish(&serialized_msg);
|
return this->do_serialized_publish(&serialized_msg);
|
||||||
}
|
}
|
||||||
|
|
||||||
/// Publish an instance of a LoanedMessage
|
/// Publish an instance of a LoanedMessage.
|
||||||
/**
|
/**
|
||||||
* When publishing a loaned message, the memory for this ROS instance will be deallocated
|
* When publishing a loaned message, the memory for this ROS message will be deallocated
|
||||||
* after being published.
|
* after being published.
|
||||||
* The instance of the loaned message is no longer valid after this call.
|
* The instance of the loaned message is no longer valid after this call.
|
||||||
*
|
*
|
||||||
|
|
|
@ -134,7 +134,6 @@ public:
|
||||||
void
|
void
|
||||||
handle_message(std::shared_ptr<void> & message, const rmw_message_info_t & message_info) = 0;
|
handle_message(std::shared_ptr<void> & message, const rmw_message_info_t & message_info) = 0;
|
||||||
|
|
||||||
// TODO(karsten1987): Does it make sense to pass in a weak_ptr?
|
|
||||||
RCLCPP_PUBLIC
|
RCLCPP_PUBLIC
|
||||||
virtual
|
virtual
|
||||||
void
|
void
|
||||||
|
|
|
@ -344,13 +344,13 @@ Executor::execute_subscription(
|
||||||
subscription->get_topic_name(), rcl_get_error_string().str);
|
subscription->get_topic_name(), rcl_get_error_string().str);
|
||||||
rcl_reset_error();
|
rcl_reset_error();
|
||||||
}
|
}
|
||||||
ret = rcl_release_loaned_message(
|
ret = rcl_return_loaned_message_from_subscription(
|
||||||
subscription->get_subscription_handle().get(),
|
subscription->get_subscription_handle().get(),
|
||||||
loaned_msg);
|
loaned_msg);
|
||||||
if (RCL_RET_OK != ret) {
|
if (RCL_RET_OK != ret) {
|
||||||
RCUTILS_LOG_ERROR_NAMED(
|
RCUTILS_LOG_ERROR_NAMED(
|
||||||
"rclcpp",
|
"rclcpp",
|
||||||
"release_loaned failed for subscription on topic '%s': %s",
|
"return_loaned_message failed for subscription on topic '%s': %s",
|
||||||
subscription->get_topic_name(), rcl_get_error_string().str);
|
subscription->get_topic_name(), rcl_get_error_string().str);
|
||||||
}
|
}
|
||||||
loaned_msg = nullptr;
|
loaned_msg = nullptr;
|
||||||
|
|
|
@ -53,7 +53,7 @@ TEST_F(TestLoanedMessage, loan_from_pub) {
|
||||||
auto node = std::make_shared<rclcpp::Node>("loaned_message_test_node");
|
auto node = std::make_shared<rclcpp::Node>("loaned_message_test_node");
|
||||||
auto pub = node->create_publisher<MessageT>("loaned_message_test_topic", 1);
|
auto pub = node->create_publisher<MessageT>("loaned_message_test_topic", 1);
|
||||||
|
|
||||||
auto loaned_msg = pub->loan_message();
|
auto loaned_msg = pub->borrow_loaned_message();
|
||||||
ASSERT_TRUE(loaned_msg.is_valid());
|
ASSERT_TRUE(loaned_msg.is_valid());
|
||||||
loaned_msg.get().float64_value = 42.0f;
|
loaned_msg.get().float64_value = 42.0f;
|
||||||
ASSERT_EQ(42.0f, loaned_msg.get().float64_value);
|
ASSERT_EQ(42.0f, loaned_msg.get().float64_value);
|
||||||
|
@ -67,7 +67,7 @@ TEST_F(TestLoanedMessage, release) {
|
||||||
|
|
||||||
MessageT * msg = nullptr;
|
MessageT * msg = nullptr;
|
||||||
{
|
{
|
||||||
auto loaned_msg = pub->loan_message();
|
auto loaned_msg = pub->borrow_loaned_message();
|
||||||
ASSERT_TRUE(loaned_msg.is_valid());
|
ASSERT_TRUE(loaned_msg.is_valid());
|
||||||
loaned_msg.get().float64_value = 42.0f;
|
loaned_msg.get().float64_value = 42.0f;
|
||||||
ASSERT_EQ(42.0f, loaned_msg.get().float64_value);
|
ASSERT_EQ(42.0f, loaned_msg.get().float64_value);
|
||||||
|
|
Loading…
Add table
Add a link
Reference in a new issue