ROS 2 rclcpp + rcl - jazzy  jazzy
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/detail/resolve_intra_process_buffer_type.hpp"
36 #include "rclcpp/experimental/buffers/intra_process_buffer.hpp"
37 #include "rclcpp/experimental/create_intra_process_buffer.hpp"
38 #include "rclcpp/experimental/intra_process_manager.hpp"
39 #include "rclcpp/get_message_type_support_handle.hpp"
40 #include "rclcpp/is_ros_compatible_type.hpp"
41 #include "rclcpp/loaned_message.hpp"
42 #include "rclcpp/macros.hpp"
43 #include "rclcpp/node_interfaces/node_base_interface.hpp"
44 #include "rclcpp/publisher_base.hpp"
45 #include "rclcpp/publisher_options.hpp"
46 #include "rclcpp/type_adapter.hpp"
47 #include "rclcpp/type_support_decl.hpp"
48 #include "rclcpp/visibility_control.hpp"
49 
50 #include "tracetools/tracetools.h"
51 
52 namespace rclcpp
53 {
54 
55 template<typename MessageT, typename AllocatorT>
56 class LoanedMessage;
57 
59 
79 template<typename MessageT, typename AllocatorT = std::allocator<void>>
80 class Publisher : public PublisherBase
81 {
82 public:
83  static_assert(
85  "given message type is not compatible with ROS and cannot be used with a Publisher");
86 
88  using PublishedType = typename rclcpp::TypeAdapter<MessageT>::custom_type;
89  using ROSMessageType = typename rclcpp::TypeAdapter<MessageT>::ros_message_type;
90 
91  using PublishedTypeAllocatorTraits = allocator::AllocRebind<PublishedType, AllocatorT>;
92  using PublishedTypeAllocator = typename PublishedTypeAllocatorTraits::allocator_type;
93  using PublishedTypeDeleter = allocator::Deleter<PublishedTypeAllocator, PublishedType>;
94 
95  using ROSMessageTypeAllocatorTraits = allocator::AllocRebind<ROSMessageType, AllocatorT>;
96  using ROSMessageTypeAllocator = typename ROSMessageTypeAllocatorTraits::allocator_type;
97  using ROSMessageTypeDeleter = allocator::Deleter<ROSMessageTypeAllocator, ROSMessageType>;
98 
99  using MessageAllocatorTraits
100  [[deprecated("use PublishedTypeAllocatorTraits")]] =
101  PublishedTypeAllocatorTraits;
102  using MessageAllocator
103  [[deprecated("use PublishedTypeAllocator")]] =
104  PublishedTypeAllocator;
105  using MessageDeleter
106  [[deprecated("use PublishedTypeDeleter")]] =
107  PublishedTypeDeleter;
108  using MessageUniquePtr
109  [[deprecated("use std::unique_ptr<PublishedType, PublishedTypeDeleter>")]] =
110  std::unique_ptr<PublishedType, PublishedTypeDeleter>;
111  using MessageSharedPtr
112  [[deprecated("use std::shared_ptr<const PublishedType>")]] =
113  std::shared_ptr<const PublishedType>;
114 
115  using BufferSharedPtr = typename rclcpp::experimental::buffers::IntraProcessBuffer<
116  ROSMessageType,
117  ROSMessageTypeAllocator,
118  ROSMessageTypeDeleter
119  >::SharedPtr;
120 
121  RCLCPP_SMART_PTR_DEFINITIONS(Publisher<MessageT, AllocatorT>)
122 
123 
135  rclcpp::node_interfaces::NodeBaseInterface * node_base,
136  const std::string & topic,
137  const rclcpp::QoS & qos,
138  const rclcpp::PublisherOptionsWithAllocator<AllocatorT> & options)
139  : PublisherBase(
140  node_base,
141  topic,
142  rclcpp::get_message_type_support_handle<MessageT>(),
143  options.template to_rcl_publisher_options<MessageT>(qos),
144  // NOTE(methylDragon): Passing these args separately is necessary for event binding
145  options.event_callbacks,
146  options.use_default_callbacks),
147  options_(options),
148  published_type_allocator_(*options.get_allocator()),
149  ros_message_type_allocator_(*options.get_allocator())
150  {
151  allocator::set_allocator_for_deleter(&published_type_deleter_, &published_type_allocator_);
152  allocator::set_allocator_for_deleter(&ros_message_type_deleter_, &ros_message_type_allocator_);
153  // Setup continues in the post construction method, post_init_setup().
154  }
155 
157  virtual
158  void
161  const std::string & topic,
162  const rclcpp::QoS & qos,
164  {
165  (void)qos;
166  (void)options;
167 
168  // If needed, setup intra process communication.
169  if (rclcpp::detail::resolve_use_intra_process(options_, *node_base)) {
170  auto context = node_base->get_context();
171  // Get the intra process manager instance for this context.
172  auto ipm = context->get_sub_context<rclcpp::experimental::IntraProcessManager>();
173  // Check if the QoS is compatible with intra-process.
174  auto qos_profile = get_actual_qos();
175  if (qos_profile.history() != rclcpp::HistoryPolicy::KeepLast) {
176  throw std::invalid_argument(
177  "intraprocess communication on topic '" + topic +
178  "' allowed only with keep last history qos policy");
179  }
180  if (qos_profile.depth() == 0) {
181  throw std::invalid_argument(
182  "intraprocess communication on topic '" + topic +
183  "' is not allowed with a zero qos history depth value");
184  }
185  if (qos_profile.durability() == rclcpp::DurabilityPolicy::TransientLocal) {
186  buffer_ = rclcpp::experimental::create_intra_process_buffer<
187  ROSMessageType, ROSMessageTypeAllocator, ROSMessageTypeDeleter>(
188  rclcpp::detail::resolve_intra_process_buffer_type(options_.intra_process_buffer_type),
189  qos_profile,
190  std::make_shared<ROSMessageTypeAllocator>(ros_message_type_allocator_));
191  }
192  // Register the publisher with the intra process manager.
193  uint64_t intra_process_publisher_id = ipm->add_publisher(this->shared_from_this(), buffer_);
194  this->setup_intra_process(
195  intra_process_publisher_id,
196  ipm);
197  }
198  }
199 
200  virtual ~Publisher()
201  {}
202 
204 
220  {
222  *this,
223  this->get_ros_message_type_allocator());
224  }
225 
227 
237  template<typename T>
238  typename std::enable_if_t<
239  rosidl_generator_traits::is_message<T>::value &&
240  std::is_same<T, ROSMessageType>::value
241  >
242  publish(std::unique_ptr<T, ROSMessageTypeDeleter> msg)
243  {
244  if (!intra_process_is_enabled_) {
245  this->do_inter_process_publish(*msg);
246  return;
247  }
248  // If an interprocess subscription exist, then the unique_ptr is promoted
249  // to a shared_ptr and published.
250  // This allows doing the intraprocess publish first and then doing the
251  // interprocess publish, resulting in lower publish-to-subscribe latency.
252  // It's not possible to do that with an unique_ptr,
253  // as do_intra_process_publish takes the ownership of the message.
254 
255  // When durability is set to TransientLocal (i.e. there is a buffer),
256  // inter process publish should always take place to ensure
257  // late joiners receive past data.
258  bool inter_process_publish_needed =
260 
261  if (inter_process_publish_needed) {
262  auto shared_msg =
263  this->do_intra_process_ros_message_publish_and_return_shared(std::move(msg));
264  if (buffer_) {
265  buffer_->add_shared(shared_msg);
266  }
267  this->do_inter_process_publish(*shared_msg);
268  } else {
269  if (buffer_) {
270  auto shared_msg =
271  this->do_intra_process_ros_message_publish_and_return_shared(std::move(msg));
272  buffer_->add_shared(shared_msg);
273  } else {
274  this->do_intra_process_ros_message_publish(std::move(msg));
275  }
276  }
277  }
278 
280 
291  template<typename T>
292  typename std::enable_if_t<
293  rosidl_generator_traits::is_message<T>::value &&
294  std::is_same<T, ROSMessageType>::value
295  >
296  publish(const T & msg)
297  {
298  // Avoid allocating when not using intra process.
299  if (!intra_process_is_enabled_) {
300  this->do_inter_process_publish(msg);
301  return;
302  }
303  // Otherwise we have to allocate memory in a unique_ptr and pass it along.
304  // As the message is not const, a copy should be made.
305  // A shared_ptr<const MessageT> could also be constructed here.
306  auto unique_msg = this->duplicate_ros_message_as_unique_ptr(msg);
307  this->publish(std::move(unique_msg));
308  }
309 
311 
321  template<typename T>
322  typename std::enable_if_t<
324  std::is_same<T, PublishedType>::value
325  >
326  publish(std::unique_ptr<T, PublishedTypeDeleter> msg)
327  {
328  if (!intra_process_is_enabled_) {
329  // In this case we're not using intra process.
330  auto ros_msg_ptr = std::make_unique<ROSMessageType>();
332  this->do_inter_process_publish(*ros_msg_ptr);
333  return;
334  }
335 
336  // When durability is set to TransientLocal (i.e. there is a buffer),
337  // inter process publish should always take place to ensure
338  // late joiners receive past data.
339  bool inter_process_publish_needed =
341 
342  if (inter_process_publish_needed) {
343  auto ros_msg_ptr = std::make_shared<ROSMessageType>();
345  this->do_intra_process_publish(std::move(msg));
346  this->do_inter_process_publish(*ros_msg_ptr);
347  if (buffer_) {
348  buffer_->add_shared(ros_msg_ptr);
349  }
350  } else {
351  if (buffer_) {
352  auto ros_msg_ptr = std::make_shared<ROSMessageType>();
354  buffer_->add_shared(ros_msg_ptr);
355  }
356  this->do_intra_process_publish(std::move(msg));
357  }
358  }
359 
361 
371  template<typename T>
372  typename std::enable_if_t<
374  std::is_same<T, PublishedType>::value
375  >
376  publish(const T & msg)
377  {
378  if (!intra_process_is_enabled_) {
379  // Convert to the ROS message equivalent and publish it.
380  auto ros_msg_ptr = std::make_unique<ROSMessageType>();
382  this->do_inter_process_publish(*ros_msg_ptr);
383  return;
384  }
385 
386  // Otherwise we have to allocate memory in a unique_ptr and pass it along.
387  // As the message is not const, a copy should be made.
388  // A shared_ptr<const MessageT> could also be constructed here.
389  auto unique_msg = this->duplicate_type_adapt_message_as_unique_ptr(msg);
390  this->publish(std::move(unique_msg));
391  }
392 
393  void
394  publish(const rcl_serialized_message_t & serialized_msg)
395  {
396  return this->do_serialized_publish(&serialized_msg);
397  }
398 
399  void
400  publish(const SerializedMessage & serialized_msg)
401  {
402  return this->do_serialized_publish(&serialized_msg.get_rcl_serialized_message());
403  }
404 
406 
413  void
415  {
416  if (!loaned_msg.is_valid()) {
417  throw std::runtime_error("loaned message is not valid");
418  }
419 
420  // verify that publisher supports loaned messages
421  // TODO(Karsten1987): This case separation has to be done in rclcpp
422  // otherwise we have to ensure that every middleware implements
423  // `rmw_publish_loaned_message` explicitly the same way as `rmw_publish`
424  // by taking a copy of the ros message.
425  if (this->can_loan_messages()) {
426  // we release the ownership from the rclpp::LoanedMessage instance
427  // and let the middleware clean up the memory.
428  this->do_loaned_message_publish(loaned_msg.release());
429  } else {
430  // we don't release the ownership, let the middleware copy the ros message
431  // and thus the destructor of rclcpp::LoanedMessage cleans up the memory.
432  this->publish(loaned_msg.get());
433  }
434  }
435 
436  [[deprecated("use get_published_type_allocator() or get_ros_message_type_allocator() instead")]]
437  std::shared_ptr<PublishedTypeAllocator>
438  get_allocator() const
439  {
440  return std::make_shared<PublishedTypeAllocator>(published_type_allocator_);
441  }
442 
443  PublishedTypeAllocator
444  get_published_type_allocator() const
445  {
446  return published_type_allocator_;
447  }
448 
449  ROSMessageTypeAllocator
450  get_ros_message_type_allocator() const
451  {
452  return ros_message_type_allocator_;
453  }
454 
455 protected:
456  void
457  do_inter_process_publish(const ROSMessageType & msg)
458  {
459  TRACETOOLS_TRACEPOINT(rclcpp_publish, nullptr, static_cast<const void *>(&msg));
460  auto status = rcl_publish(publisher_handle_.get(), &msg, nullptr);
461 
462  if (RCL_RET_PUBLISHER_INVALID == status) {
463  rcl_reset_error(); // next call will reset error message if not context
464  if (rcl_publisher_is_valid_except_context(publisher_handle_.get())) {
465  rcl_context_t * context = rcl_publisher_get_context(publisher_handle_.get());
466  if (nullptr != context && !rcl_context_is_valid(context)) {
467  // publisher is invalid due to context being shutdown
468  return;
469  }
470  }
471  }
472  if (RCL_RET_OK != status) {
473  rclcpp::exceptions::throw_from_rcl_error(status, "failed to publish message");
474  }
475  }
476 
477  void
478  do_serialized_publish(const rcl_serialized_message_t * serialized_msg)
479  {
480  if (intra_process_is_enabled_) {
481  // TODO(Karsten1987): support serialized message passed by intraprocess
482  throw std::runtime_error("storing serialized messages in intra process is not supported yet");
483  }
484  auto status = rcl_publish_serialized_message(publisher_handle_.get(), serialized_msg, nullptr);
485  if (RCL_RET_OK != status) {
486  rclcpp::exceptions::throw_from_rcl_error(status, "failed to publish serialized message");
487  }
488  }
489 
490  void
491  do_loaned_message_publish(
492  std::unique_ptr<ROSMessageType, std::function<void(ROSMessageType *)>> msg)
493  {
494  TRACETOOLS_TRACEPOINT(rclcpp_publish, nullptr, static_cast<const void *>(msg.get()));
495  auto status = rcl_publish_loaned_message(publisher_handle_.get(), msg.get(), nullptr);
496 
497  if (RCL_RET_PUBLISHER_INVALID == status) {
498  rcl_reset_error(); // next call will reset error message if not context
499  if (rcl_publisher_is_valid_except_context(publisher_handle_.get())) {
500  rcl_context_t * context = rcl_publisher_get_context(publisher_handle_.get());
501  if (nullptr != context && !rcl_context_is_valid(context)) {
502  // publisher is invalid due to context being shutdown
503  return;
504  }
505  }
506  }
507  if (RCL_RET_OK != status) {
508  rclcpp::exceptions::throw_from_rcl_error(status, "failed to publish message");
509  }
510  }
511 
512  void
513  do_intra_process_publish(std::unique_ptr<PublishedType, PublishedTypeDeleter> msg)
514  {
515  auto ipm = weak_ipm_.lock();
516  if (!ipm) {
517  throw std::runtime_error(
518  "intra process publish called after destruction of intra process manager");
519  }
520  if (!msg) {
521  throw std::runtime_error("cannot publish msg which is a null pointer");
522  }
523  TRACETOOLS_TRACEPOINT(
524  rclcpp_intra_publish,
525  static_cast<const void *>(publisher_handle_.get()),
526  msg.get());
527 
528  ipm->template do_intra_process_publish<PublishedType, ROSMessageType, AllocatorT>(
529  intra_process_publisher_id_,
530  std::move(msg),
531  published_type_allocator_);
532  }
533 
534  void
535  do_intra_process_ros_message_publish(std::unique_ptr<ROSMessageType, ROSMessageTypeDeleter> msg)
536  {
537  auto ipm = weak_ipm_.lock();
538  if (!ipm) {
539  throw std::runtime_error(
540  "intra process publish called after destruction of intra process manager");
541  }
542  if (!msg) {
543  throw std::runtime_error("cannot publish msg which is a null pointer");
544  }
545  TRACETOOLS_TRACEPOINT(
546  rclcpp_intra_publish,
547  static_cast<const void *>(publisher_handle_.get()),
548  msg.get());
549 
550  ipm->template do_intra_process_publish<ROSMessageType, ROSMessageType, AllocatorT>(
551  intra_process_publisher_id_,
552  std::move(msg),
553  ros_message_type_allocator_);
554  }
555 
556  std::shared_ptr<const ROSMessageType>
557  do_intra_process_ros_message_publish_and_return_shared(
558  std::unique_ptr<ROSMessageType, ROSMessageTypeDeleter> msg)
559  {
560  auto ipm = weak_ipm_.lock();
561  if (!ipm) {
562  throw std::runtime_error(
563  "intra process publish called after destruction of intra process manager");
564  }
565  if (!msg) {
566  throw std::runtime_error("cannot publish msg which is a null pointer");
567  }
568  TRACETOOLS_TRACEPOINT(
569  rclcpp_intra_publish,
570  static_cast<const void *>(publisher_handle_.get()),
571  msg.get());
572 
573  return ipm->template do_intra_process_publish_and_return_shared<ROSMessageType, ROSMessageType,
574  AllocatorT>(
575  intra_process_publisher_id_,
576  std::move(msg),
577  ros_message_type_allocator_);
578  }
579 
580 
582  std::unique_ptr<ROSMessageType, ROSMessageTypeDeleter>
584  {
585  auto ptr = ROSMessageTypeAllocatorTraits::allocate(ros_message_type_allocator_, 1);
586  ROSMessageTypeAllocatorTraits::construct(ros_message_type_allocator_, ptr);
587  return std::unique_ptr<ROSMessageType, ROSMessageTypeDeleter>(ptr, ros_message_type_deleter_);
588  }
589 
591  std::unique_ptr<ROSMessageType, ROSMessageTypeDeleter>
592  duplicate_ros_message_as_unique_ptr(const ROSMessageType & msg)
593  {
594  auto ptr = ROSMessageTypeAllocatorTraits::allocate(ros_message_type_allocator_, 1);
595  ROSMessageTypeAllocatorTraits::construct(ros_message_type_allocator_, ptr, msg);
596  return std::unique_ptr<ROSMessageType, ROSMessageTypeDeleter>(ptr, ros_message_type_deleter_);
597  }
598 
600  std::unique_ptr<PublishedType, PublishedTypeDeleter>
602  {
603  auto ptr = PublishedTypeAllocatorTraits::allocate(published_type_allocator_, 1);
604  PublishedTypeAllocatorTraits::construct(published_type_allocator_, ptr, msg);
605  return std::unique_ptr<PublishedType, PublishedTypeDeleter>(ptr, published_type_deleter_);
606  }
607 
609 
614 
615  PublishedTypeAllocator published_type_allocator_;
616  PublishedTypeDeleter published_type_deleter_;
617  ROSMessageTypeAllocator ros_message_type_allocator_;
618  ROSMessageTypeDeleter ros_message_type_deleter_;
619 
620  BufferSharedPtr buffer_{nullptr};
621 };
622 
623 } // namespace rclcpp
624 
625 #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:81
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:159
typename rclcpp::TypeAdapter< MessageT >::custom_type PublishedType
MessageT::custom_type if MessageT is a TypeAdapter, otherwise just MessageT.
Definition: publisher.hpp:88
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:326
const rclcpp::PublisherOptionsWithAllocator< AllocatorT > options_
Copy of original options passed during construction.
Definition: publisher.hpp:613
rclcpp::LoanedMessage< ROSMessageType, AllocatorT > borrow_loaned_message()
Borrow a loaned ROS message from the middleware.
Definition: publisher.hpp:219
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:592
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:242
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:376
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:601
std::unique_ptr< ROSMessageType, ROSMessageTypeDeleter > create_ros_message_unique_ptr()
Return a new unique_ptr using the ROSMessageType of the publisher.
Definition: publisher.hpp:583
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:296
void publish(rclcpp::LoanedMessage< ROSMessageType, AllocatorT > &&loaned_msg)
Publish an instance of a LoanedMessage.
Definition: publisher.hpp:414
Encapsulation of Quality of Service settings.
Definition: qos.hpp:116
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:314
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:291
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:408
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:270
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:432
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:27
rmw_serialized_message_t rcl_serialized_message_t
typedef for rmw_serialized_message_t;
Definition: types.h:134
#define RCL_RET_PUBLISHER_INVALID
Invalid rcl_publisher_t given return code.
Definition: types.h:69