rclcpp  master
C++ ROS Client Library API
publisher.hpp
Go to the documentation of this file.
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 <rmw/error_handling.h>
19 #include <rmw/rmw.h>
20 
21 #include <functional>
22 #include <iostream>
23 #include <memory>
24 #include <sstream>
25 #include <string>
26 
27 #include "rcl/error_handling.h"
28 #include "rcl/publisher.h"
29 
30 #include "rcl_interfaces/msg/intra_process_message.hpp"
31 
34 #include "rclcpp/macros.hpp"
38 
39 namespace rclcpp
40 {
41 
42 // Forward declaration is used for friend statement.
43 namespace node_interfaces
44 {
45 class NodeTopicsInterface;
46 }
47 
48 namespace publisher
49 {
50 
52 {
54 
55 public:
57 
58 
59 
70  const std::string & topic,
71  const rosidl_message_type_support_t & type_support,
72  const rcl_publisher_options_t & publisher_options);
73 
75  virtual ~PublisherBase();
76 
78 
80  const char *
81  get_topic_name() const;
82 
84 
86  size_t
87  get_queue_size() const;
88 
90 
92  const rmw_gid_t &
93  get_gid() const;
94 
96 
98  const rmw_gid_t &
99  get_intra_process_gid() const;
100 
102 
105  get_publisher_handle();
106 
108 
110  const rcl_publisher_t *
111  get_publisher_handle() const;
112 
114 
120  bool
121  operator==(const rmw_gid_t & gid) const;
122 
124 
130  bool
131  operator==(const rmw_gid_t * gid) const;
132 
134 
137  void
138  setup_intra_process(
139  uint64_t intra_process_publisher_id,
140  StoreMessageCallbackT callback,
141  const rcl_publisher_options_t & intra_process_options);
142 
143 protected:
145 
147  rcl_publisher_t intra_process_publisher_handle_ = rcl_get_zero_initialized_publisher();
148 
151 
154 };
155 
157 template<typename MessageT, typename Alloc = std::allocator<void>>
158 class Publisher : public PublisherBase
159 {
160 public:
162  using MessageAlloc = typename MessageAllocTraits::allocator_type;
165 
167 
169  rclcpp::node_interfaces::NodeBaseInterface * node_base,
170  const std::string & topic,
171  const rcl_publisher_options_t & publisher_options,
172  const std::shared_ptr<MessageAlloc> & allocator)
173  : PublisherBase(
174  node_base,
175  topic,
176  *rosidl_typesupport_cpp::get_message_type_support_handle<MessageT>(),
177  publisher_options),
178  message_allocator_(allocator)
179  {
180  allocator::set_allocator_for_deleter(&message_deleter_, message_allocator_.get());
181  }
182 
183  virtual ~Publisher()
184  {}
185 
187 
191  virtual void
193  {
194  this->do_inter_process_publish(msg.get());
195  if (store_intra_process_message_) {
196  // Take the pointer from the unique_msg, release it and pass as a void *
197  // to the ipm. The ipm should then capture it again as a unique_ptr of
198  // the correct type.
199  // TODO(wjwwood):
200  // investigate how to transfer the custom deleter (if there is one)
201  // from the incoming unique_ptr through to the ipm's unique_ptr.
202  // See: http://stackoverflow.com/questions/11002641/dynamic-casting-for-unique-ptr
203  MessageT * msg_ptr = msg.get();
204  msg.release();
205  uint64_t message_seq =
206  store_intra_process_message_(intra_process_publisher_id_, msg_ptr, typeid(MessageT));
207  rcl_interfaces::msg::IntraProcessMessage ipm;
208  ipm.publisher_id = intra_process_publisher_id_;
209  ipm.message_sequence = message_seq;
210  auto status = rcl_publish(&intra_process_publisher_handle_, &ipm);
211  if (status != RCL_RET_OK) {
212  // *INDENT-OFF* (prevent uncrustify from making unnecessary indents here)
213  throw std::runtime_error(
214  std::string("failed to publish intra process message: ") + rcl_get_error_string_safe());
215  // *INDENT-ON*
216  }
217  } else {
218  // Always destroy the message, even if we don't consume it, for consistency.
219  msg.reset();
220  }
221  }
222 
223  virtual void
225  {
226  // Avoid allocating when not using intra process.
227  if (!store_intra_process_message_) {
228  // In this case we're not using intra process.
229  return this->do_inter_process_publish(msg.get());
230  }
231  // Otherwise we have to allocate memory in a unique_ptr and pass it along.
232  // TODO(wjwwood):
233  // The intra process manager should probably also be able to store
234  // shared_ptr's and do the "smart" thing based on other intra process
235  // subscriptions. For now call the other publish().
236  auto ptr = MessageAllocTraits::allocate(*message_allocator_.get(), 1);
237  MessageAllocTraits::construct(*message_allocator_.get(), ptr, *msg.get());
238  MessageUniquePtr unique_msg(ptr, message_deleter_);
239  return this->publish(unique_msg);
240  }
241 
242  virtual void
244  {
245  // Avoid allocating when not using intra process.
246  if (!store_intra_process_message_) {
247  // In this case we're not using intra process.
248  return this->do_inter_process_publish(msg.get());
249  }
250  // Otherwise we have to allocate memory in a unique_ptr and pass it along.
251  // TODO(wjwwood):
252  // The intra process manager should probably also be able to store
253  // shared_ptr's and do the "smart" thing based on other intra process
254  // subscriptions. For now call the other publish().
255  auto ptr = MessageAllocTraits::allocate(*message_allocator_.get(), 1);
256  MessageAllocTraits::construct(*message_allocator_.get(), ptr, *msg.get());
257  MessageUniquePtr unique_msg(ptr, message_deleter_);
258  return this->publish(unique_msg);
259  }
260 
261  virtual void
262  publish(const MessageT & msg)
263  {
264  // Avoid allocating when not using intra process.
265  if (!store_intra_process_message_) {
266  // In this case we're not using intra process.
267  return this->do_inter_process_publish(&msg);
268  }
269  // Otherwise we have to allocate memory in a unique_ptr and pass it along.
270  auto ptr = MessageAllocTraits::allocate(*message_allocator_.get(), 1);
271  MessageAllocTraits::construct(*message_allocator_.get(), ptr, msg);
272  MessageUniquePtr unique_msg(ptr, message_deleter_);
273  return this->publish(unique_msg);
274  }
275 
276  virtual void
277  publish(const MessageT * msg)
278  {
279  if (!msg) {
280  throw std::runtime_error("msg argument is nullptr");
281  }
282  return this->publish(*msg);
283  }
284 
286  {
287  return message_allocator_;
288  }
289 
290 protected:
291  void
292  do_inter_process_publish(const MessageT * msg)
293  {
294  auto status = rcl_publish(&publisher_handle_, msg);
295  if (status != RCL_RET_OK) {
296  // *INDENT-OFF* (prevent uncrustify from making unnecessary indents here)
297  throw std::runtime_error(
298  std::string("failed to publish message: ") + rcl_get_error_string_safe());
299  // *INDENT-ON*
300  }
301  }
302 
304 
306 };
307 
308 } // namespace publisher
309 
310 } // namespace rclcpp
311 
312 #endif // RCLCPP__PUBLISHER_HPP_
uint64_t intra_process_publisher_id_
Definition: publisher.hpp:149
MessageDeleter message_deleter_
Definition: publisher.hpp:305
Definition: allocator_common.hpp:24
virtual void publish(std::unique_ptr< MessageT, MessageDeleter > &msg)
Send a message to the topic for this publisher.
Definition: publisher.hpp:192
Definition: publisher.hpp:51
virtual ~Publisher()
Definition: publisher.hpp:183
std::shared_ptr< MessageAlloc > message_allocator_
Definition: publisher.hpp:303
T release(T... args)
#define RCL_RET_OK
std::shared_ptr< rcl_node_t > rcl_node_handle_
Definition: publisher.hpp:144
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:163
typename MessageAllocTraits::allocator_type MessageAlloc
Definition: publisher.hpp:162
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:285
StoreMessageCallbackT store_intra_process_message_
Definition: publisher.hpp:150
Pure virtual interface class for the NodeBase part of the Node API.
Definition: node_base_interface.hpp:36
T reset(T... args)
#define rcl_get_error_string_safe
rmw_gid_t rmw_gid_
Definition: publisher.hpp:152
virtual void publish(std::shared_ptr< const MessageT > msg)
Definition: publisher.hpp:243
T get(T... args)
#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:153
virtual void publish(const MessageT &msg)
Definition: publisher.hpp:262
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:292
allocator::AllocRebind< rcl_interfaces::msg::ParameterEvent, std::allocator< void > > MessageAllocTraits
Definition: publisher.hpp:161
rcl_ret_t rcl_publish(const rcl_publisher_t *publisher, const void *ros_message)
virtual void publish(const MessageT *msg)
Definition: publisher.hpp:277
A publisher publishes messages of any type to a topic.
Definition: publisher.hpp:158
virtual void publish(const std::shared_ptr< MessageT > &msg)
Definition: publisher.hpp:224