15 #ifndef RCLCPP__PUBLISHER_HPP_ 16 #define RCLCPP__PUBLISHER_HPP_ 30 #include "rcl_interfaces/msg/intra_process_message.hpp" 43 namespace node_interfaces
45 class NodeTopicsInterface;
70 const std::string & topic,
71 const rosidl_message_type_support_t & type_support,
75 virtual ~PublisherBase();
81 get_topic_name()
const;
87 get_queue_size()
const;
99 get_intra_process_gid()
const;
127 uint64_t intra_process_publisher_id,
145 template<
typename MessageT,
typename Alloc = std::allocator<
void>>
157 rclcpp::node_interfaces::NodeBaseInterface * node_base,
158 const
std::
string & topic,
164 *rosidl_typesupport_cpp::get_message_type_support_handle<MessageT>(),
166 message_allocator_(allocator)
180 publish(std::unique_ptr<MessageT, MessageDeleter> & msg)
182 this->do_inter_process_publish(msg.get());
183 if (store_intra_process_message_) {
191 MessageT * msg_ptr = msg.get();
193 uint64_t message_seq =
194 store_intra_process_message_(intra_process_publisher_id_, msg_ptr,
typeid(MessageT));
195 rcl_interfaces::msg::IntraProcessMessage ipm;
196 ipm.publisher_id = intra_process_publisher_id_;
197 ipm.message_sequence = message_seq;
198 auto status =
rcl_publish(&intra_process_publisher_handle_, &ipm);
201 throw std::runtime_error(
212 publish(
const std::shared_ptr<MessageT> & msg)
215 if (!store_intra_process_message_) {
217 return this->do_inter_process_publish(msg.get());
224 auto ptr = MessageAllocTraits::allocate(*message_allocator_.get(), 1);
225 MessageAllocTraits::construct(*message_allocator_.get(), ptr, *msg.get());
227 return this->publish(unique_msg);
234 if (!store_intra_process_message_) {
236 return this->do_inter_process_publish(msg.get());
243 auto ptr = MessageAllocTraits::allocate(*message_allocator_.get(), 1);
244 MessageAllocTraits::construct(*message_allocator_.get(), ptr, *msg.get());
246 return this->publish(unique_msg);
253 if (!store_intra_process_message_) {
255 return this->do_inter_process_publish(&msg);
258 auto ptr = MessageAllocTraits::allocate(*message_allocator_.get(), 1);
259 MessageAllocTraits::construct(*message_allocator_.get(), ptr, msg);
261 return this->publish(unique_msg);
268 throw std::runtime_error(
"msg argument is nullptr");
270 return this->publish(*msg);
275 return message_allocator_;
282 auto status =
rcl_publish(&publisher_handle_, msg);
285 throw std::runtime_error(
300 #endif // RCLCPP__PUBLISHER_HPP_ uint64_t intra_process_publisher_id_
Definition: publisher.hpp:137
MessageDeleter message_deleter_
Definition: publisher.hpp:293
Definition: allocator_common.hpp:24
Definition: parameter.hpp:235
virtual void publish(std::unique_ptr< MessageT, MessageDeleter > &msg)
Send a message to the topic for this publisher.
Definition: publisher.hpp:180
std::function< uint64_t(uint64_t, void *, const std::type_info &)> StoreMessageCallbackT
Definition: publisher.hpp:121
Definition: publisher.hpp:51
virtual ~Publisher()
Definition: publisher.hpp:171
std::shared_ptr< MessageAlloc > message_allocator_
Definition: publisher.hpp:291
std::unique_ptr< rcl_interfaces::msg::ParameterEvent, MessageDeleter > MessageUniquePtr
Definition: publisher.hpp:152
std::shared_ptr< rcl_node_t > rcl_node_handle_
Definition: publisher.hpp:132
void set_allocator_for_deleter(D *deleter, Alloc *alloc)
Definition: allocator_deleter.hpp:72
allocator::Deleter< MessageAlloc, rcl_interfaces::msg::ParameterEvent > MessageDeleter
Definition: publisher.hpp:151
typename MessageAllocTraits::allocator_type MessageAlloc
Definition: publisher.hpp:150
typename std::allocator_traits< Alloc >::template rebind_traits< T > AllocRebind
Definition: allocator_common.hpp:30
rcl_publisher_t rcl_get_zero_initialized_publisher(void)
#define RCLCPP_SMART_PTR_DEFINITIONS(...)
Definition: macros.hpp:36
std::shared_ptr< MessageAlloc > get_allocator() const
Definition: publisher.hpp:273
StoreMessageCallbackT store_intra_process_message_
Definition: publisher.hpp:138
Pure virtual interface class for the NodeBase part of the Node API.
Definition: node_base_interface.hpp:36
#define rcl_get_error_string_safe
rmw_gid_t rmw_gid_
Definition: publisher.hpp:140
virtual void publish(std::shared_ptr< const MessageT > msg)
Definition: publisher.hpp:231
#define RCLCPP_PUBLIC
Definition: visibility_control.hpp:50
Pure virtual interface class for the NodeTopics part of the Node API.
Definition: node_topics_interface.hpp:38
rmw_gid_t intra_process_rmw_gid_
Definition: publisher.hpp:141
virtual void publish(const MessageT &msg)
Definition: publisher.hpp:250
typename std::conditional< std::is_same< typename std::allocator_traits< Alloc >::template rebind_alloc< T >, typename std::allocator< void >::template rebind< T >::other >::value, std::default_delete< T >, AllocatorDeleter< Alloc > >::type Deleter
Definition: allocator_deleter.hpp:101
void do_inter_process_publish(const MessageT *msg)
Definition: publisher.hpp:280
allocator::AllocRebind< rcl_interfaces::msg::ParameterEvent, std::allocator< void > > MessageAllocTraits
Definition: publisher.hpp:149
rcl_ret_t rcl_publish(const rcl_publisher_t *publisher, const void *ros_message)
virtual void publish(const MessageT *msg)
Definition: publisher.hpp:265
A publisher publishes messages of any type to a topic.
Definition: publisher.hpp:146
virtual void publish(const std::shared_ptr< MessageT > &msg)
Definition: publisher.hpp:212