ROS 2 rclcpp + rcl - humble  humble
ROS 2 C++ Client Library with ROS Client Library
publisher.hpp
1 // Copyright 2014 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__PUBLISHER_HPP_
16 #define RCLCPP__PUBLISHER_HPP_
17 
18 #include <functional>
19 #include <iostream>
20 #include <memory>
21 #include <sstream>
22 #include <string>
23 #include <type_traits>
24 #include <utility>
25 
26 #include "rcl/error_handling.h"
27 #include "rcl/publisher.h"
28 #include "rmw/error_handling.h"
29 #include "rmw/rmw.h"
30 #include "rosidl_runtime_cpp/traits.hpp"
31 
32 #include "rclcpp/allocator/allocator_common.hpp"
33 #include "rclcpp/allocator/allocator_deleter.hpp"
34 #include "rclcpp/detail/resolve_use_intra_process.hpp"
35 #include "rclcpp/experimental/intra_process_manager.hpp"
36 #include "rclcpp/get_message_type_support_handle.hpp"
37 #include "rclcpp/is_ros_compatible_type.hpp"
38 #include "rclcpp/loaned_message.hpp"
39 #include "rclcpp/macros.hpp"
40 #include "rclcpp/node_interfaces/node_base_interface.hpp"
41 #include "rclcpp/publisher_base.hpp"
42 #include "rclcpp/publisher_options.hpp"
43 #include "rclcpp/type_adapter.hpp"
44 #include "rclcpp/type_support_decl.hpp"
45 #include "rclcpp/visibility_control.hpp"
46 
47 #include "tracetools/tracetools.h"
48 
49 namespace rclcpp
50 {
51 
52 template<typename MessageT, typename AllocatorT>
53 class LoanedMessage;
54 
56 
76 template<typename MessageT, typename AllocatorT = std::allocator<void>>
77 class Publisher : public PublisherBase
78 {
79 public:
80  static_assert(
82  "given message type is not compatible with ROS and cannot be used with a Publisher");
83 
85  using PublishedType = typename rclcpp::TypeAdapter<MessageT>::custom_type;
86  using ROSMessageType = typename rclcpp::TypeAdapter<MessageT>::ros_message_type;
87 
88  using PublishedTypeAllocatorTraits = allocator::AllocRebind<PublishedType, AllocatorT>;
89  using PublishedTypeAllocator = typename PublishedTypeAllocatorTraits::allocator_type;
90  using PublishedTypeDeleter = allocator::Deleter<PublishedTypeAllocator, PublishedType>;
91 
92  using ROSMessageTypeAllocatorTraits = allocator::AllocRebind<ROSMessageType, AllocatorT>;
93  using ROSMessageTypeAllocator = typename ROSMessageTypeAllocatorTraits::allocator_type;
94  using ROSMessageTypeDeleter = allocator::Deleter<ROSMessageTypeAllocator, ROSMessageType>;
95 
96  using MessageAllocatorTraits
97  [[deprecated("use PublishedTypeAllocatorTraits")]] =
98  PublishedTypeAllocatorTraits;
99  using MessageAllocator
100  [[deprecated("use PublishedTypeAllocator")]] =
101  PublishedTypeAllocator;
102  using MessageDeleter
103  [[deprecated("use PublishedTypeDeleter")]] =
104  PublishedTypeDeleter;
105  using MessageUniquePtr
106  [[deprecated("use std::unique_ptr<PublishedType, PublishedTypeDeleter>")]] =
107  std::unique_ptr<PublishedType, PublishedTypeDeleter>;
108  using MessageSharedPtr
109  [[deprecated("use std::shared_ptr<const PublishedType>")]] =
110  std::shared_ptr<const PublishedType>;
111 
112  RCLCPP_SMART_PTR_DEFINITIONS(Publisher<MessageT, AllocatorT>)
113 
114 
126  rclcpp::node_interfaces::NodeBaseInterface * node_base,
127  const std::string & topic,
128  const rclcpp::QoS & qos,
129  const rclcpp::PublisherOptionsWithAllocator<AllocatorT> & options)
130  : PublisherBase(
131  node_base,
132  topic,
133  rclcpp::get_message_type_support_handle<MessageT>(),
134  options.template to_rcl_publisher_options<MessageT>(qos)),
135  options_(options),
136  published_type_allocator_(*options.get_allocator()),
137  ros_message_type_allocator_(*options.get_allocator())
138  {
139  allocator::set_allocator_for_deleter(&published_type_deleter_, &published_type_allocator_);
140  allocator::set_allocator_for_deleter(&ros_message_type_deleter_, &ros_message_type_allocator_);
141 
142  if (options_.event_callbacks.deadline_callback) {
143  this->add_event_handler(
144  options_.event_callbacks.deadline_callback,
145  RCL_PUBLISHER_OFFERED_DEADLINE_MISSED);
146  }
147  if (options_.event_callbacks.liveliness_callback) {
148  this->add_event_handler(
149  options_.event_callbacks.liveliness_callback,
150  RCL_PUBLISHER_LIVELINESS_LOST);
151  }
152  if (options_.event_callbacks.incompatible_qos_callback) {
153  this->add_event_handler(
154  options_.event_callbacks.incompatible_qos_callback,
155  RCL_PUBLISHER_OFFERED_INCOMPATIBLE_QOS);
156  } else if (options_.use_default_callbacks) {
157  // Register default callback when not specified
158  try {
159  this->add_event_handler(
160  [this](QOSOfferedIncompatibleQoSInfo & info) {
161  this->default_incompatible_qos_callback(info);
162  },
163  RCL_PUBLISHER_OFFERED_INCOMPATIBLE_QOS);
164  } catch (UnsupportedEventTypeException & /*exc*/) {
165  // pass
166  }
167  }
168  // Setup continues in the post construction method, post_init_setup().
169  }
170 
172  virtual
173  void
176  const std::string & topic,
177  const rclcpp::QoS & qos,
179  {
180  (void)qos;
181  (void)options;
182 
183  // If needed, setup intra process communication.
184  if (rclcpp::detail::resolve_use_intra_process(options_, *node_base)) {
185  auto context = node_base->get_context();
186  // Get the intra process manager instance for this context.
187  auto ipm = context->get_sub_context<rclcpp::experimental::IntraProcessManager>();
188  // Check if the QoS is compatible with intra-process.
189  auto qos_profile = get_actual_qos();
190  if (qos_profile.history() != rclcpp::HistoryPolicy::KeepLast) {
191  throw std::invalid_argument(
192  "intraprocess communication on topic '" + topic +
193  "' allowed only with keep last history qos policy");
194  }
195  if (qos_profile.depth() == 0) {
196  throw std::invalid_argument(
197  "intraprocess communication on topic '" + topic +
198  "' is not allowed with a zero qos history depth value");
199  }
200  if (qos_profile.durability() != rclcpp::DurabilityPolicy::Volatile) {
201  throw std::invalid_argument(
202  "intraprocess communication allowed only with volatile durability");
203  }
204  // Register the publisher with the intra process manager.
205  uint64_t intra_process_publisher_id = ipm->add_publisher(this->shared_from_this());
206  this->setup_intra_process(
207  intra_process_publisher_id,
208  ipm);
209  }
210  }
211 
212  virtual ~Publisher()
213  {}
214 
216 
232  {
234  *this,
235  this->get_ros_message_type_allocator());
236  }
237 
239 
249  template<typename T>
250  typename std::enable_if_t<
251  rosidl_generator_traits::is_message<T>::value &&
252  std::is_same<T, ROSMessageType>::value
253  >
254  publish(std::unique_ptr<T, ROSMessageTypeDeleter> msg)
255  {
256  if (!intra_process_is_enabled_) {
257  this->do_inter_process_publish(*msg);
258  return;
259  }
260  // If an interprocess subscription exist, then the unique_ptr is promoted
261  // to a shared_ptr and published.
262  // This allows doing the intraprocess publish first and then doing the
263  // interprocess publish, resulting in lower publish-to-subscribe latency.
264  // It's not possible to do that with an unique_ptr,
265  // as do_intra_process_publish takes the ownership of the message.
266  bool inter_process_publish_needed =
268 
269  if (inter_process_publish_needed) {
270  auto shared_msg =
271  this->do_intra_process_ros_message_publish_and_return_shared(std::move(msg));
272  this->do_inter_process_publish(*shared_msg);
273  } else {
274  this->do_intra_process_ros_message_publish(std::move(msg));
275  }
276  }
277 
279 
290  template<typename T>
291  typename std::enable_if_t<
292  rosidl_generator_traits::is_message<T>::value &&
293  std::is_same<T, ROSMessageType>::value
294  >
295  publish(const T & msg)
296  {
297  // Avoid allocating when not using intra process.
298  if (!intra_process_is_enabled_) {
299  // In this case we're not using intra process.
300  return this->do_inter_process_publish(msg);
301  }
302  // Otherwise we have to allocate memory in a unique_ptr and pass it along.
303  // As the message is not const, a copy should be made.
304  // A shared_ptr<const MessageT> could also be constructed here.
305  auto unique_msg = this->duplicate_ros_message_as_unique_ptr(msg);
306  this->publish(std::move(unique_msg));
307  }
308 
310 
320  template<typename T>
321  typename std::enable_if_t<
323  std::is_same<T, PublishedType>::value
324  >
325  publish(std::unique_ptr<T, PublishedTypeDeleter> msg)
326  {
327  // Avoid allocating when not using intra process.
328  if (!intra_process_is_enabled_) {
329  // In this case we're not using intra process.
330  ROSMessageType ros_msg;
332  return this->do_inter_process_publish(ros_msg);
333  }
334 
335  bool inter_process_publish_needed =
337 
338  if (inter_process_publish_needed) {
339  ROSMessageType ros_msg;
340  // TODO(clalancette): This is unnecessarily doing an additional conversion
341  // that may have already been done in do_intra_process_publish_and_return_shared().
342  // We should just reuse that effort.
344  this->do_intra_process_publish(std::move(msg));
345  this->do_inter_process_publish(ros_msg);
346  } else {
347  this->do_intra_process_publish(std::move(msg));
348  }
349  }
350 
352 
362  template<typename T>
363  typename std::enable_if_t<
365  std::is_same<T, PublishedType>::value
366  >
367  publish(const T & msg)
368  {
369  // Avoid double allocating when not using intra process.
370  if (!intra_process_is_enabled_) {
371  // Convert to the ROS message equivalent and publish it.
372  ROSMessageType ros_msg;
374  // In this case we're not using intra process.
375  return this->do_inter_process_publish(ros_msg);
376  }
377 
378  // Otherwise we have to allocate memory in a unique_ptr and pass it along.
379  // As the message is not const, a copy should be made.
380  // A shared_ptr<const MessageT> could also be constructed here.
381  auto unique_msg = this->duplicate_type_adapt_message_as_unique_ptr(msg);
382  this->publish(std::move(unique_msg));
383  }
384 
385  void
386  publish(const rcl_serialized_message_t & serialized_msg)
387  {
388  return this->do_serialized_publish(&serialized_msg);
389  }
390 
391  void
392  publish(const SerializedMessage & serialized_msg)
393  {
394  return this->do_serialized_publish(&serialized_msg.get_rcl_serialized_message());
395  }
396 
398 
405  void
407  {
408  if (!loaned_msg.is_valid()) {
409  throw std::runtime_error("loaned message is not valid");
410  }
411  if (intra_process_is_enabled_) {
412  // TODO(Karsten1987): support loaned message passed by intraprocess
413  throw std::runtime_error("storing loaned messages in intra process is not supported yet");
414  }
415 
416  // verify that publisher supports loaned messages
417  // TODO(Karsten1987): This case separation has to be done in rclcpp
418  // otherwise we have to ensure that every middleware implements
419  // `rmw_publish_loaned_message` explicitly the same way as `rmw_publish`
420  // by taking a copy of the ros message.
421  if (this->can_loan_messages()) {
422  // we release the ownership from the rclpp::LoanedMessage instance
423  // and let the middleware clean up the memory.
424  this->do_loaned_message_publish(std::move(loaned_msg.release()));
425  } else {
426  // we don't release the ownership, let the middleware copy the ros message
427  // and thus the destructor of rclcpp::LoanedMessage cleans up the memory.
428  this->do_inter_process_publish(loaned_msg.get());
429  }
430  }
431 
432  [[deprecated("use get_published_type_allocator() or get_ros_message_type_allocator() instead")]]
433  std::shared_ptr<PublishedTypeAllocator>
434  get_allocator() const
435  {
436  return std::make_shared<PublishedTypeAllocator>(published_type_allocator_);
437  }
438 
439  PublishedTypeAllocator
440  get_published_type_allocator() const
441  {
442  return published_type_allocator_;
443  }
444 
445  ROSMessageTypeAllocator
446  get_ros_message_type_allocator() const
447  {
448  return ros_message_type_allocator_;
449  }
450 
451 protected:
452  void
453  do_inter_process_publish(const ROSMessageType & msg)
454  {
455  TRACEPOINT(rclcpp_publish, nullptr, static_cast<const void *>(&msg));
456  auto status = rcl_publish(publisher_handle_.get(), &msg, nullptr);
457 
458  if (RCL_RET_PUBLISHER_INVALID == status) {
459  rcl_reset_error(); // next call will reset error message if not context
460  if (rcl_publisher_is_valid_except_context(publisher_handle_.get())) {
461  rcl_context_t * context = rcl_publisher_get_context(publisher_handle_.get());
462  if (nullptr != context && !rcl_context_is_valid(context)) {
463  // publisher is invalid due to context being shutdown
464  return;
465  }
466  }
467  }
468  if (RCL_RET_OK != status) {
469  rclcpp::exceptions::throw_from_rcl_error(status, "failed to publish message");
470  }
471  }
472 
473  void
474  do_serialized_publish(const rcl_serialized_message_t * serialized_msg)
475  {
476  if (intra_process_is_enabled_) {
477  // TODO(Karsten1987): support serialized message passed by intraprocess
478  throw std::runtime_error("storing serialized messages in intra process is not supported yet");
479  }
480  auto status = rcl_publish_serialized_message(publisher_handle_.get(), serialized_msg, nullptr);
481  if (RCL_RET_OK != status) {
482  rclcpp::exceptions::throw_from_rcl_error(status, "failed to publish serialized message");
483  }
484  }
485 
486  void
487  do_loaned_message_publish(
488  std::unique_ptr<ROSMessageType, std::function<void(ROSMessageType *)>> msg)
489  {
490  auto status = rcl_publish_loaned_message(publisher_handle_.get(), msg.get(), nullptr);
491 
492  if (RCL_RET_PUBLISHER_INVALID == status) {
493  rcl_reset_error(); // next call will reset error message if not context
494  if (rcl_publisher_is_valid_except_context(publisher_handle_.get())) {
495  rcl_context_t * context = rcl_publisher_get_context(publisher_handle_.get());
496  if (nullptr != context && !rcl_context_is_valid(context)) {
497  // publisher is invalid due to context being shutdown
498  return;
499  }
500  }
501  }
502  if (RCL_RET_OK != status) {
503  rclcpp::exceptions::throw_from_rcl_error(status, "failed to publish message");
504  }
505  }
506 
507  void
508  do_intra_process_publish(std::unique_ptr<PublishedType, PublishedTypeDeleter> msg)
509  {
510  auto ipm = weak_ipm_.lock();
511  if (!ipm) {
512  throw std::runtime_error(
513  "intra process publish called after destruction of intra process manager");
514  }
515  if (!msg) {
516  throw std::runtime_error("cannot publish msg which is a null pointer");
517  }
518 
519  ipm->template do_intra_process_publish<PublishedType, ROSMessageType, AllocatorT>(
520  intra_process_publisher_id_,
521  std::move(msg),
522  published_type_allocator_);
523  }
524 
525  void
526  do_intra_process_ros_message_publish(std::unique_ptr<ROSMessageType, ROSMessageTypeDeleter> msg)
527  {
528  auto ipm = weak_ipm_.lock();
529  if (!ipm) {
530  throw std::runtime_error(
531  "intra process publish called after destruction of intra process manager");
532  }
533  if (!msg) {
534  throw std::runtime_error("cannot publish msg which is a null pointer");
535  }
536 
537  ipm->template do_intra_process_publish<ROSMessageType, ROSMessageType, AllocatorT>(
538  intra_process_publisher_id_,
539  std::move(msg),
540  ros_message_type_allocator_);
541  }
542 
543  std::shared_ptr<const ROSMessageType>
544  do_intra_process_ros_message_publish_and_return_shared(
545  std::unique_ptr<ROSMessageType, ROSMessageTypeDeleter> msg)
546  {
547  auto ipm = weak_ipm_.lock();
548  if (!ipm) {
549  throw std::runtime_error(
550  "intra process publish called after destruction of intra process manager");
551  }
552  if (!msg) {
553  throw std::runtime_error("cannot publish msg which is a null pointer");
554  }
555 
556  return ipm->template do_intra_process_publish_and_return_shared<ROSMessageType, ROSMessageType,
557  AllocatorT>(
558  intra_process_publisher_id_,
559  std::move(msg),
560  ros_message_type_allocator_);
561  }
562 
563 
565  std::unique_ptr<ROSMessageType, ROSMessageTypeDeleter>
567  {
568  auto ptr = ROSMessageTypeAllocatorTraits::allocate(ros_message_type_allocator_, 1);
569  ROSMessageTypeAllocatorTraits::construct(ros_message_type_allocator_, ptr);
570  return std::unique_ptr<ROSMessageType, ROSMessageTypeDeleter>(ptr, ros_message_type_deleter_);
571  }
572 
574  std::unique_ptr<ROSMessageType, ROSMessageTypeDeleter>
575  duplicate_ros_message_as_unique_ptr(const ROSMessageType & msg)
576  {
577  auto ptr = ROSMessageTypeAllocatorTraits::allocate(ros_message_type_allocator_, 1);
578  ROSMessageTypeAllocatorTraits::construct(ros_message_type_allocator_, ptr, msg);
579  return std::unique_ptr<ROSMessageType, ROSMessageTypeDeleter>(ptr, ros_message_type_deleter_);
580  }
581 
583  std::unique_ptr<PublishedType, PublishedTypeDeleter>
585  {
586  auto ptr = PublishedTypeAllocatorTraits::allocate(published_type_allocator_, 1);
587  PublishedTypeAllocatorTraits::construct(published_type_allocator_, ptr, msg);
588  return std::unique_ptr<PublishedType, PublishedTypeDeleter>(ptr, published_type_deleter_);
589  }
590 
592 
597 
598  PublishedTypeAllocator published_type_allocator_;
599  PublishedTypeDeleter published_type_deleter_;
600  ROSMessageTypeAllocator ros_message_type_allocator_;
601  ROSMessageTypeDeleter ros_message_type_deleter_;
602 };
603 
604 } // namespace rclcpp
605 
606 #endif // RCLCPP__PUBLISHER_HPP_
RCLCPP_PUBLIC size_t get_intra_process_subscription_count() const
Get intraprocess subscription count.
RCLCPP_PUBLIC rclcpp::QoS get_actual_qos() const
Get the actual QoS settings, after the defaults have been determined.
RCLCPP_PUBLIC void setup_intra_process(uint64_t intra_process_publisher_id, IntraProcessManagerSharedPtr ipm)
Implementation utility function used to setup intra process publishing after creation.
RCLCPP_PUBLIC bool can_loan_messages() const
Check if publisher instance can loan messages.
RCLCPP_PUBLIC size_t get_subscription_count() const
Get subscription count.
A publisher publishes messages of any type to a topic.
Definition: publisher.hpp:78
virtual void post_init_setup(rclcpp::node_interfaces::NodeBaseInterface *node_base, const std::string &topic, const rclcpp::QoS &qos, const rclcpp::PublisherOptionsWithAllocator< AllocatorT > &options)
Called post construction, so that construction may continue after shared_from_this() works.
Definition: publisher.hpp:174
typename rclcpp::TypeAdapter< MessageT >::custom_type PublishedType
MessageT::custom_type if MessageT is a TypeAdapter, otherwise just MessageT.
Definition: publisher.hpp:85
std::enable_if_t< rclcpp::TypeAdapter< MessageT >::is_specialized::value &&std::is_same< T, PublishedType >::value > publish(std::unique_ptr< T, PublishedTypeDeleter > msg)
Publish a message on the topic.
Definition: publisher.hpp:325
const rclcpp::PublisherOptionsWithAllocator< AllocatorT > options_
Copy of original options passed during construction.
Definition: publisher.hpp:596
rclcpp::LoanedMessage< ROSMessageType, AllocatorT > borrow_loaned_message()
Borrow a loaned ROS message from the middleware.
Definition: publisher.hpp:231
std::unique_ptr< ROSMessageType, ROSMessageTypeDeleter > duplicate_ros_message_as_unique_ptr(const ROSMessageType &msg)
Duplicate a given ros message as a unique_ptr.
Definition: publisher.hpp:575
std::enable_if_t< rosidl_generator_traits::is_message< T >::value &&std::is_same< T, ROSMessageType >::value > publish(std::unique_ptr< T, ROSMessageTypeDeleter > msg)
Publish a message on the topic.
Definition: publisher.hpp:254
std::enable_if_t< rclcpp::TypeAdapter< MessageT >::is_specialized::value &&std::is_same< T, PublishedType >::value > publish(const T &msg)
Publish a message on the topic.
Definition: publisher.hpp:367
std::unique_ptr< PublishedType, PublishedTypeDeleter > duplicate_type_adapt_message_as_unique_ptr(const PublishedType &msg)
Duplicate a given type adapted message as a unique_ptr.
Definition: publisher.hpp:584
std::unique_ptr< ROSMessageType, ROSMessageTypeDeleter > create_ros_message_unique_ptr()
Return a new unique_ptr using the ROSMessageType of the publisher.
Definition: publisher.hpp:566
std::enable_if_t< rosidl_generator_traits::is_message< T >::value &&std::is_same< T, ROSMessageType >::value > publish(const T &msg)
Publish a message on the topic.
Definition: publisher.hpp:295
void publish(rclcpp::LoanedMessage< ROSMessageType, AllocatorT > &&loaned_msg)
Publish an instance of a LoanedMessage.
Definition: publisher.hpp:406
Encapsulation of Quality of Service settings.
Definition: qos.hpp:111
This class performs intra process communication between nodes.
Pure virtual interface class for the NodeBase part of the Node API.
virtual RCLCPP_PUBLIC rclcpp::Context::SharedPtr get_context()=0
Return the context of the node.
RCL_PUBLIC RCL_WARN_UNUSED bool rcl_context_is_valid(const rcl_context_t *context)
Return true if the given context is currently valid, otherwise false.
Definition: context.c:94
Versions of rosidl_typesupport_cpp::get_message_type_support_handle that handle adapted types.
RCL_PUBLIC RCL_WARN_UNUSED rcl_ret_t rcl_publish_loaned_message(const rcl_publisher_t *publisher, void *ros_message, rmw_publisher_allocation_t *allocation)
Publish a loaned message on a topic using a publisher.
Definition: publisher.c:279
RCL_PUBLIC RCL_WARN_UNUSED rcl_ret_t rcl_publish_serialized_message(const rcl_publisher_t *publisher, const rcl_serialized_message_t *serialized_message, rmw_publisher_allocation_t *allocation)
Publish a serialized message on a topic using a publisher.
Definition: publisher.c:257
RCL_PUBLIC RCL_WARN_UNUSED rcl_context_t * rcl_publisher_get_context(const rcl_publisher_t *publisher)
Return the context associated with this publisher.
Definition: publisher.c:374
RCL_PUBLIC RCL_WARN_UNUSED rcl_ret_t rcl_publish(const rcl_publisher_t *publisher, const void *ros_message, rmw_publisher_allocation_t *allocation)
Publish a ROS message on a topic using a publisher.
Definition: publisher.c:236
RCL_PUBLIC bool rcl_publisher_is_valid_except_context(const rcl_publisher_t *publisher)
Return true if the publisher is valid except the context, otherwise false.
Definition: publisher.c:398
Encapsulates the non-global state of an init/shutdown cycle.
Definition: context.h:114
Structure containing optional configuration for Publishers.
Template structure used to adapt custom, user-defined types to ROS types.
#define RCL_RET_OK
Success return code.
Definition: types.h:26
rmw_serialized_message_t rcl_serialized_message_t
typedef for rmw_serialized_message_t;
Definition: types.h:127
#define RCL_RET_PUBLISHER_INVALID
Invalid rcl_publisher_t given return code.
Definition: types.h:66