ROS 2 rclcpp + rcl - jazzy  jazzy
ROS 2 C++ Client Library with ROS Client Library
loaned_message.hpp
1 // Copyright 2019 Open Source Robotics Foundation, Inc.
2 //
3 // Licensed under the Apache License, Version 2.0 (the "License");
4 // you may not use this file except in compliance with the License.
5 // You may obtain a copy of the License at
6 //
7 // http://www.apache.org/licenses/LICENSE-2.0
8 //
9 // Unless required by applicable law or agreed to in writing, software
10 // distributed under the License is distributed on an "AS IS" BASIS,
11 // WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
12 // See the License for the specific language governing permissions and
13 // limitations under the License.
14 
15 #ifndef RCLCPP__LOANED_MESSAGE_HPP_
16 #define RCLCPP__LOANED_MESSAGE_HPP_
17 
18 #include <memory>
19 #include <utility>
20 
21 #include "rclcpp/allocator/allocator_common.hpp"
22 #include "rclcpp/logging.hpp"
23 #include "rclcpp/publisher_base.hpp"
24 
25 #include "rcl/allocator.h"
26 #include "rcl/publisher.h"
27 
28 namespace rclcpp
29 {
30 
31 template<typename MessageT, typename AllocatorT = std::allocator<void>>
33 {
34  using MessageAllocatorTraits = rclcpp::allocator::AllocRebind<MessageT, AllocatorT>;
35  using MessageAllocator = typename MessageAllocatorTraits::allocator_type;
36 
37 public:
39 
60  const rclcpp::PublisherBase & pub,
61  std::allocator<MessageT> allocator)
62  : pub_(pub),
63  message_(nullptr),
64  message_allocator_(std::move(allocator))
65  {
66  if (pub_.can_loan_messages()) {
67  void * message_ptr = nullptr;
68  auto ret = rcl_borrow_loaned_message(
69  pub_.get_publisher_handle().get(),
70  rosidl_typesupport_cpp::get_message_type_support_handle<MessageT>(),
71  &message_ptr);
72  if (RCL_RET_OK != ret) {
73  rclcpp::exceptions::throw_from_rcl_error(ret);
74  }
75  message_ = static_cast<MessageT *>(message_ptr);
76  } else {
77  RCLCPP_INFO_ONCE(
78  rclcpp::get_logger("rclcpp"),
79  "Currently used middleware can't loan messages. Local allocator will be used.");
80  message_ = message_allocator_.allocate(1);
81  new (message_) MessageT();
82  }
83  }
84 
86 
106  [[
107  deprecated("used the LoanedMessage constructor that does not use a shared_ptr to the allocator")
108  ]]
110  const rclcpp::PublisherBase * pub,
111  std::shared_ptr<std::allocator<MessageT>> allocator)
112  : LoanedMessage(*pub, *allocator)
113  {}
114 
117  : pub_(std::move(other.pub_)),
118  message_(std::move(other.message_)),
119  message_allocator_(std::move(other.message_allocator_))
120  {
121  other.message_ = nullptr;
122  }
123 
125 
136  virtual ~LoanedMessage()
137  {
138  auto error_logger = rclcpp::get_logger("LoanedMessage");
139 
140  if (message_ == nullptr) {
141  return;
142  }
143 
144  if (pub_.can_loan_messages()) {
145  // return allocated memory to the middleware
146  auto ret =
148  if (ret != RCL_RET_OK) {
149  RCLCPP_ERROR(
150  error_logger, "rcl_deallocate_loaned_message failed: %s", rcl_get_error_string().str);
151  rcl_reset_error();
152  }
153  } else {
154  // call destructor before deallocating
155  message_->~MessageT();
156  message_allocator_.deallocate(message_, 1);
157  }
158  message_ = nullptr;
159  }
160 
162 
169  bool is_valid() const
170  {
171  return message_ != nullptr;
172  }
173 
175 
182  MessageT & get() const
183  {
184  return *message_;
185  }
186 
188 
198  std::unique_ptr<MessageT, std::function<void(MessageT *)>>
200  {
201  auto msg = message_;
202  message_ = nullptr;
203 
204  if (pub_.can_loan_messages()) {
205  return std::unique_ptr<MessageT, std::function<void(MessageT *)>>(msg, [](MessageT *) {});
206  }
207 
208  return std::unique_ptr<MessageT, std::function<void(MessageT *)>>(
209  msg,
210  [allocator = message_allocator_](MessageT * msg_ptr) mutable {
211  // call destructor before deallocating
212  msg_ptr->~MessageT();
213  allocator.deallocate(msg_ptr, 1);
214  });
215  }
216 
217 protected:
218  const rclcpp::PublisherBase & pub_;
219 
220  MessageT * message_;
221 
222  MessageAllocator message_allocator_;
223 
225  LoanedMessage(const LoanedMessage<MessageT> & other) = delete;
226 };
227 
228 } // namespace rclcpp
229 
230 #endif // RCLCPP__LOANED_MESSAGE_HPP_
std::unique_ptr< MessageT, std::function< void(MessageT *)> > release()
Release ownership of the ROS message instance.
LoanedMessage(const LoanedMessage< MessageT > &other)=delete
Deleted copy constructor to preserve memory integrity.
LoanedMessage(const rclcpp::PublisherBase *pub, std::shared_ptr< std::allocator< MessageT >> allocator)
Constructor of the LoanedMessage class.
MessageT & get() const
Access the ROS message instance.
LoanedMessage(const rclcpp::PublisherBase &pub, std::allocator< MessageT > allocator)
Constructor of the LoanedMessage class.
LoanedMessage(LoanedMessage< MessageT > &&other)
Move semantic for RVO.
virtual ~LoanedMessage()
Destructor of the LoanedMessage class.
bool is_valid() const
Validate if the message was correctly allocated.
RCLCPP_PUBLIC std::shared_ptr< rcl_publisher_t > get_publisher_handle()
Get the rcl publisher handle.
RCLCPP_PUBLIC bool can_loan_messages() const
Check if publisher instance can loan messages.
Versions of rosidl_typesupport_cpp::get_message_type_support_handle that handle adapted types.
RCLCPP_PUBLIC Logger get_logger(const std::string &name)
Return a named logger.
Definition: logger.cpp:33
RCL_PUBLIC RCL_WARN_UNUSED rcl_ret_t rcl_borrow_loaned_message(const rcl_publisher_t *publisher, const rosidl_message_type_support_t *type_support, void **ros_message)
Borrow a loaned message.
Definition: publisher.c:244
RCL_PUBLIC RCL_WARN_UNUSED rcl_ret_t rcl_return_loaned_message_from_publisher(const rcl_publisher_t *publisher, void *loaned_message)
Return a loaned message previously borrowed from a publisher.
Definition: publisher.c:257
#define RCL_RET_OK
Success return code.
Definition: types.h:27