15 #ifndef RCLCPP__PUBLISHER_HPP_
16 #define RCLCPP__PUBLISHER_HPP_
23 #include <type_traits>
26 #include "rcl/error_handling.h"
28 #include "rmw/error_handling.h"
30 #include "rosidl_runtime_cpp/traits.hpp"
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"
47 #include "tracetools/tracetools.h"
52 template<
typename MessageT,
typename AllocatorT>
76 template<
typename MessageT,
typename AllocatorT = std::allocator<
void>>
82 "given message type is not compatible with ROS and cannot be used with a Publisher");
85 using PublishedType =
typename rclcpp::TypeAdapter<MessageT>::custom_type;
86 using ROSMessageType =
typename rclcpp::TypeAdapter<MessageT>::ros_message_type;
88 using PublishedTypeAllocatorTraits = allocator::AllocRebind<PublishedType, AllocatorT>;
89 using PublishedTypeAllocator =
typename PublishedTypeAllocatorTraits::allocator_type;
90 using PublishedTypeDeleter = allocator::Deleter<PublishedTypeAllocator, PublishedType>;
92 using ROSMessageTypeAllocatorTraits = allocator::AllocRebind<ROSMessageType, AllocatorT>;
93 using ROSMessageTypeAllocator =
typename ROSMessageTypeAllocatorTraits::allocator_type;
94 using ROSMessageTypeDeleter = allocator::Deleter<ROSMessageTypeAllocator, ROSMessageType>;
96 using MessageAllocatorTraits
97 [[deprecated(
"use PublishedTypeAllocatorTraits")]] =
98 PublishedTypeAllocatorTraits;
99 using MessageAllocator
100 [[deprecated(
"use PublishedTypeAllocator")]] =
101 PublishedTypeAllocator;
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>;
126 rclcpp::node_interfaces::NodeBaseInterface * node_base,
127 const std::
string & topic,
133 rclcpp::get_message_type_support_handle<MessageT>(),
134 options.template to_rcl_publisher_options<MessageT>(qos)),
136 published_type_allocator_(*options.get_allocator()),
137 ros_message_type_allocator_(*options.get_allocator())
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_);
142 if (
options_.event_callbacks.deadline_callback) {
143 this->add_event_handler(
144 options_.event_callbacks.deadline_callback,
145 RCL_PUBLISHER_OFFERED_DEADLINE_MISSED);
147 if (
options_.event_callbacks.liveliness_callback) {
148 this->add_event_handler(
149 options_.event_callbacks.liveliness_callback,
150 RCL_PUBLISHER_LIVELINESS_LOST);
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) {
159 this->add_event_handler(
160 [
this](QOSOfferedIncompatibleQoSInfo & info) {
161 this->default_incompatible_qos_callback(info);
163 RCL_PUBLISHER_OFFERED_INCOMPATIBLE_QOS);
176 const std::string & topic,
184 if (rclcpp::detail::resolve_use_intra_process(
options_, *node_base)) {
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");
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");
200 if (qos_profile.durability() != rclcpp::DurabilityPolicy::Volatile) {
201 throw std::invalid_argument(
202 "intraprocess communication allowed only with volatile durability");
205 uint64_t intra_process_publisher_id = ipm->add_publisher(this->shared_from_this());
207 intra_process_publisher_id,
235 this->get_ros_message_type_allocator());
250 typename std::enable_if_t<
251 rosidl_generator_traits::is_message<T>::value &&
252 std::is_same<T, ROSMessageType>::value
254 publish(std::unique_ptr<T, ROSMessageTypeDeleter> msg)
256 if (!intra_process_is_enabled_) {
257 this->do_inter_process_publish(*msg);
266 bool inter_process_publish_needed =
269 if (inter_process_publish_needed) {
271 this->do_intra_process_ros_message_publish_and_return_shared(std::move(msg));
272 this->do_inter_process_publish(*shared_msg);
274 this->do_intra_process_ros_message_publish(std::move(msg));
291 typename std::enable_if_t<
292 rosidl_generator_traits::is_message<T>::value &&
293 std::is_same<T, ROSMessageType>::value
298 if (!intra_process_is_enabled_) {
300 return this->do_inter_process_publish(msg);
306 this->
publish(std::move(unique_msg));
321 typename std::enable_if_t<
323 std::is_same<T, PublishedType>::value
325 publish(std::unique_ptr<T, PublishedTypeDeleter> msg)
328 if (!intra_process_is_enabled_) {
330 ROSMessageType ros_msg;
332 return this->do_inter_process_publish(ros_msg);
335 bool inter_process_publish_needed =
338 if (inter_process_publish_needed) {
339 ROSMessageType ros_msg;
344 this->do_intra_process_publish(std::move(msg));
345 this->do_inter_process_publish(ros_msg);
347 this->do_intra_process_publish(std::move(msg));
363 typename std::enable_if_t<
365 std::is_same<T, PublishedType>::value
370 if (!intra_process_is_enabled_) {
372 ROSMessageType ros_msg;
375 return this->do_inter_process_publish(ros_msg);
382 this->
publish(std::move(unique_msg));
388 return this->do_serialized_publish(&serialized_msg);
392 publish(
const SerializedMessage & serialized_msg)
394 return this->do_serialized_publish(&serialized_msg.get_rcl_serialized_message());
408 if (!loaned_msg.is_valid()) {
409 throw std::runtime_error(
"loaned message is not valid");
411 if (intra_process_is_enabled_) {
413 throw std::runtime_error(
"storing loaned messages in intra process is not supported yet");
424 this->do_loaned_message_publish(std::move(loaned_msg.release()));
428 this->do_inter_process_publish(loaned_msg.get());
432 [[deprecated(
"use get_published_type_allocator() or get_ros_message_type_allocator() instead")]]
433 std::shared_ptr<PublishedTypeAllocator>
434 get_allocator()
const
436 return std::make_shared<PublishedTypeAllocator>(published_type_allocator_);
439 PublishedTypeAllocator
440 get_published_type_allocator()
const
442 return published_type_allocator_;
445 ROSMessageTypeAllocator
446 get_ros_message_type_allocator()
const
448 return ros_message_type_allocator_;
453 do_inter_process_publish(
const ROSMessageType & msg)
455 TRACEPOINT(rclcpp_publish,
nullptr,
static_cast<const void *
>(&msg));
456 auto status =
rcl_publish(publisher_handle_.get(), &msg,
nullptr);
469 rclcpp::exceptions::throw_from_rcl_error(status,
"failed to publish message");
476 if (intra_process_is_enabled_) {
478 throw std::runtime_error(
"storing serialized messages in intra process is not supported yet");
482 rclcpp::exceptions::throw_from_rcl_error(status,
"failed to publish serialized message");
487 do_loaned_message_publish(
488 std::unique_ptr<ROSMessageType, std::function<
void(ROSMessageType *)>> msg)
503 rclcpp::exceptions::throw_from_rcl_error(status,
"failed to publish message");
508 do_intra_process_publish(std::unique_ptr<PublishedType, PublishedTypeDeleter> msg)
510 auto ipm = weak_ipm_.lock();
512 throw std::runtime_error(
513 "intra process publish called after destruction of intra process manager");
516 throw std::runtime_error(
"cannot publish msg which is a null pointer");
519 ipm->template do_intra_process_publish<PublishedType, ROSMessageType, AllocatorT>(
520 intra_process_publisher_id_,
522 published_type_allocator_);
526 do_intra_process_ros_message_publish(std::unique_ptr<ROSMessageType, ROSMessageTypeDeleter> msg)
528 auto ipm = weak_ipm_.lock();
530 throw std::runtime_error(
531 "intra process publish called after destruction of intra process manager");
534 throw std::runtime_error(
"cannot publish msg which is a null pointer");
537 ipm->template do_intra_process_publish<ROSMessageType, ROSMessageType, AllocatorT>(
538 intra_process_publisher_id_,
540 ros_message_type_allocator_);
543 std::shared_ptr<const ROSMessageType>
544 do_intra_process_ros_message_publish_and_return_shared(
545 std::unique_ptr<ROSMessageType, ROSMessageTypeDeleter> msg)
547 auto ipm = weak_ipm_.lock();
549 throw std::runtime_error(
550 "intra process publish called after destruction of intra process manager");
553 throw std::runtime_error(
"cannot publish msg which is a null pointer");
556 return ipm->template do_intra_process_publish_and_return_shared<ROSMessageType, ROSMessageType,
558 intra_process_publisher_id_,
560 ros_message_type_allocator_);
565 std::unique_ptr<ROSMessageType, ROSMessageTypeDeleter>
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_);
574 std::unique_ptr<ROSMessageType, ROSMessageTypeDeleter>
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_);
583 std::unique_ptr<PublishedType, PublishedTypeDeleter>
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_);
598 PublishedTypeAllocator published_type_allocator_;
599 PublishedTypeDeleter published_type_deleter_;
600 ROSMessageTypeAllocator ros_message_type_allocator_;
601 ROSMessageTypeDeleter ros_message_type_deleter_;
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.
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.
typename rclcpp::TypeAdapter< MessageT >::custom_type PublishedType
MessageT::custom_type if MessageT is a TypeAdapter, otherwise just MessageT.
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.
const rclcpp::PublisherOptionsWithAllocator< AllocatorT > options_
Copy of original options passed during construction.
rclcpp::LoanedMessage< ROSMessageType, AllocatorT > borrow_loaned_message()
Borrow a loaned ROS message from the middleware.
std::unique_ptr< ROSMessageType, ROSMessageTypeDeleter > duplicate_ros_message_as_unique_ptr(const ROSMessageType &msg)
Duplicate a given ros message as a unique_ptr.
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.
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.
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.
std::unique_ptr< ROSMessageType, ROSMessageTypeDeleter > create_ros_message_unique_ptr()
Return a new unique_ptr using the ROSMessageType of the publisher.
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.
void publish(rclcpp::LoanedMessage< ROSMessageType, AllocatorT > &&loaned_msg)
Publish an instance of a LoanedMessage.
Encapsulation of Quality of Service settings.
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.
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.
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.
RCL_PUBLIC RCL_WARN_UNUSED rcl_context_t * rcl_publisher_get_context(const rcl_publisher_t *publisher)
Return the context associated with this publisher.
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.
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.
Encapsulates the non-global state of an init/shutdown cycle.
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.
rmw_serialized_message_t rcl_serialized_message_t
typedef for rmw_serialized_message_t;
#define RCL_RET_PUBLISHER_INVALID
Invalid rcl_publisher_t given return code.