ROS 2 rclcpp + rcl - rolling  rolling-a919a6e5
ROS 2 C++ Client Library with ROS Client Library
event_handler.hpp
1 // Copyright 2019 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__EVENT_HANDLER_HPP_
16 #define RCLCPP__EVENT_HANDLER_HPP_
17 
18 #include <functional>
19 #include <memory>
20 #include <mutex>
21 #include <stdexcept>
22 #include <string>
23 #include <vector>
24 
25 #include "rcl/error_handling.h"
26 #include "rcl/event_callback.h"
27 #include "rmw/impl/cpp/demangle.hpp"
28 #include "rmw/incompatible_qos_events_statuses.h"
29 #include "rmw/events_statuses/incompatible_type.h"
30 
31 #include "rcutils/logging_macros.h"
32 
33 #include "rclcpp/detail/cpp_callback_trampoline.hpp"
34 #include "rclcpp/exceptions.hpp"
35 #include "rclcpp/function_traits.hpp"
36 #include "rclcpp/logging.hpp"
37 #include "rclcpp/waitable.hpp"
38 
39 namespace rclcpp
40 {
41 
42 using QOSDeadlineRequestedInfo = rmw_requested_deadline_missed_status_t;
43 using QOSDeadlineOfferedInfo = rmw_offered_deadline_missed_status_t;
44 using QOSLivelinessChangedInfo = rmw_liveliness_changed_status_t;
45 using QOSLivelinessLostInfo = rmw_liveliness_lost_status_t;
46 using QOSMessageLostInfo = rmw_message_lost_status_t;
47 using QOSOfferedIncompatibleQoSInfo = rmw_offered_qos_incompatible_event_status_t;
48 using QOSRequestedIncompatibleQoSInfo = rmw_requested_qos_incompatible_event_status_t;
49 
50 using IncompatibleTypeInfo = rmw_incompatible_type_status_t;
51 using MatchedInfo = rmw_matched_status_t;
52 
53 using QOSDeadlineRequestedCallbackType = std::function<void (QOSDeadlineRequestedInfo &)>;
54 using QOSDeadlineOfferedCallbackType = std::function<void (QOSDeadlineOfferedInfo &)>;
55 using QOSLivelinessChangedCallbackType = std::function<void (QOSLivelinessChangedInfo &)>;
56 using QOSLivelinessLostCallbackType = std::function<void (QOSLivelinessLostInfo &)>;
57 using QOSMessageLostCallbackType = std::function<void (QOSMessageLostInfo &)>;
58 using QOSOfferedIncompatibleQoSCallbackType = std::function<void (QOSOfferedIncompatibleQoSInfo &)>;
59 using QOSRequestedIncompatibleQoSCallbackType =
60  std::function<void (QOSRequestedIncompatibleQoSInfo &)>;
61 
62 using IncompatibleTypeCallbackType = std::function<void (IncompatibleTypeInfo &)>;
63 using PublisherMatchedCallbackType = std::function<void (MatchedInfo &)>;
64 using SubscriptionMatchedCallbackType = std::function<void (MatchedInfo &)>;
65 
68 {
69  QOSDeadlineOfferedCallbackType deadline_callback;
70  QOSLivelinessLostCallbackType liveliness_callback;
71  QOSOfferedIncompatibleQoSCallbackType incompatible_qos_callback;
72  IncompatibleTypeCallbackType incompatible_type_callback;
73  PublisherMatchedCallbackType matched_callback;
74 };
75 
78 {
79  QOSDeadlineRequestedCallbackType deadline_callback;
80  QOSLivelinessChangedCallbackType liveliness_callback;
81  QOSRequestedIncompatibleQoSCallbackType incompatible_qos_callback;
82  QOSMessageLostCallbackType message_lost_callback;
83  IncompatibleTypeCallbackType incompatible_type_callback;
84  SubscriptionMatchedCallbackType matched_callback;
85 };
86 
87 class UnsupportedEventTypeException : public exceptions::RCLErrorBase, public std::runtime_error
88 {
89 public:
90  RCLCPP_PUBLIC
92  rcl_ret_t ret,
93  const rcl_error_state_t * error_state,
94  const std::string & prefix);
95 
96  RCLCPP_PUBLIC
98  const exceptions::RCLErrorBase & base_exc,
99  const std::string & prefix);
100 };
101 
103 {
104 public:
105  enum class EntityType : std::size_t
106  {
107  Event,
108  };
109 
110  RCLCPP_PUBLIC
111  virtual ~EventHandlerBase();
112 
114  RCLCPP_PUBLIC
115  size_t
116  get_number_of_ready_events() override;
117 
119  RCLCPP_PUBLIC
120  void
121  add_to_wait_set(rcl_wait_set_t & wait_set) override;
122 
124  RCLCPP_PUBLIC
125  bool
126  is_ready(const rcl_wait_set_t & wait_set) override;
127 
129 
164  void
165  set_on_ready_callback(std::function<void(size_t, int)> callback) override
166  {
167  if (!callback) {
168  throw std::invalid_argument(
169  "The callback passed to set_on_ready_callback "
170  "is not callable.");
171  }
172 
173  // Note: we bind the int identifier argument to this waitable's entity types
174  auto new_callback =
175  [callback, this](size_t number_of_events) {
176  try {
177  callback(number_of_events, static_cast<int>(EntityType::Event));
178  } catch (const std::exception & exception) {
179  RCLCPP_ERROR_STREAM(
180  // TODO(wjwwood): get this class access to the node logger it is associated with
181  rclcpp::get_logger("rclcpp"),
182  "rclcpp::EventHandlerBase@" << this <<
183  " caught " << rmw::impl::cpp::demangle(exception) <<
184  " exception in user-provided callback for the 'on ready' callback: " <<
185  exception.what());
186  } catch (...) {
187  RCLCPP_ERROR_STREAM(
188  rclcpp::get_logger("rclcpp"),
189  "rclcpp::EventHandlerBase@" << this <<
190  " caught unhandled exception in user-provided callback " <<
191  "for the 'on ready' callback");
192  }
193  };
194 
195  std::lock_guard<std::recursive_mutex> lock(callback_mutex_);
196 
197  // Set it temporarily to the new callback, while we replace the old one.
198  // This two-step setting, prevents a gap where the old std::function has
199  // been replaced but the middleware hasn't been told about the new one yet.
200  set_on_new_event_callback(
201  rclcpp::detail::cpp_callback_trampoline<decltype(new_callback), const void *, size_t>,
202  static_cast<const void *>(&new_callback));
203 
204  // Store the std::function to keep it in scope, also overwrites the existing one.
205  on_new_event_callback_ = new_callback;
206 
207  // Set it again, now using the permanent storage.
208  set_on_new_event_callback(
209  rclcpp::detail::cpp_callback_trampoline<
210  decltype(on_new_event_callback_), const void *, size_t>,
211  static_cast<const void *>(&on_new_event_callback_));
212  }
213 
215  void
217  {
218  std::lock_guard<std::recursive_mutex> lock(callback_mutex_);
219  if (on_new_event_callback_) {
220  set_on_new_event_callback(nullptr, nullptr);
221  on_new_event_callback_ = nullptr;
222  }
223  }
224 
225  RCLCPP_PUBLIC
226  std::vector<std::shared_ptr<rclcpp::TimerBase>>
227  get_timers() const override
228  {
229  return {};
230  }
231 
232 protected:
233  RCLCPP_PUBLIC
234  void
235  set_on_new_event_callback(rcl_event_callback_t callback, const void * user_data);
236 
237  std::recursive_mutex callback_mutex_;
238  std::function<void(size_t)> on_new_event_callback_{nullptr};
239 
240  rcl_event_t event_handle_;
241  size_t wait_set_event_index_;
242 };
243 
244 template<typename EventCallbackT, typename ParentHandleT>
246 {
247 public:
248  template<typename InitFuncT, typename EventTypeEnum>
249  EventHandler(
250  const EventCallbackT & callback,
251  InitFuncT init_func,
252  ParentHandleT parent_handle,
253  EventTypeEnum event_type)
254  : parent_handle_(parent_handle), event_callback_(callback)
255  {
256  event_handle_ = rcl_get_zero_initialized_event();
257  rcl_ret_t ret = init_func(&event_handle_, parent_handle.get(), event_type);
258  if (ret != RCL_RET_OK) {
259  if (ret == RCL_RET_UNSUPPORTED) {
260  UnsupportedEventTypeException exc(ret, rcl_get_error_state(), "Failed to initialize event");
261  rcl_reset_error();
262  throw exc;
263  } else {
264  rclcpp::exceptions::throw_from_rcl_error(ret, "Failed to initialize event");
265  }
266  }
267  }
268 
269  ~EventHandler()
270  {
271  // Since the rmw event listener holds a reference to the
272  // "on ready" callback, we need to clear it on destruction of this class.
273  // This clearing is not needed for other rclcpp entities like pub/subs, since
274  // they do own the underlying rmw entities, which are destroyed
275  // on their rclcpp destructors, thus no risk of dangling pointers.
277  }
278 
280  std::shared_ptr<void>
281  take_data() override
282  {
283  EventCallbackInfoT callback_info;
284  rcl_ret_t ret = rcl_take_event(&event_handle_, &callback_info);
285  if (ret != RCL_RET_OK) {
286  RCUTILS_LOG_ERROR_NAMED(
287  "rclcpp",
288  "Couldn't take event info: %s", rcl_get_error_string().str);
289  rcl_reset_error();
290  return nullptr;
291  }
292  return std::static_pointer_cast<void>(std::make_shared<EventCallbackInfoT>(callback_info));
293  }
294 
295  std::shared_ptr<void>
296  take_data_by_entity_id([[maybe_unused]] size_t id) override
297  {
298  return take_data();
299  }
300 
302  void
303  execute(const std::shared_ptr<void> & data) override
304  {
305  if (!data) {
306  throw std::runtime_error("'data' is empty");
307  }
308  auto callback_ptr = std::static_pointer_cast<EventCallbackInfoT>(data);
309  event_callback_(*callback_ptr);
310  callback_ptr.reset();
311  }
312 
313 private:
314  using EventCallbackInfoT = typename std::remove_reference<typename
316 
317  ParentHandleT parent_handle_;
318  EventCallbackT event_callback_;
319 };
320 } // namespace rclcpp
321 
322 #endif // RCLCPP__EVENT_HANDLER_HPP_
RCLCPP_PUBLIC size_t get_number_of_ready_events() override
Get the number of ready events.
RCLCPP_PUBLIC void add_to_wait_set(rcl_wait_set_t &wait_set) override
Add the Waitable to a wait set.
void set_on_ready_callback(std::function< void(size_t, int)> callback) override
Set a callback to be called when each new event instance occurs.
RCLCPP_PUBLIC std::vector< std::shared_ptr< rclcpp::TimerBase > > get_timers() const override
Returns all timers used by this waitable.
RCLCPP_PUBLIC bool is_ready(const rcl_wait_set_t &wait_set) override
Check if the Waitable is ready.
void clear_on_ready_callback() override
Unset the callback registered for new events, if any.
void execute(const std::shared_ptr< void > &data) override
Execute any entities of the Waitable that are ready.
std::shared_ptr< void > take_data() override
Take data so that the callback cannot be scheduled again.
RCL_PUBLIC RCL_WARN_UNUSED rcl_ret_t rcl_take_event(const rcl_event_t *event, void *event_info)
Definition: event.c:164
RCL_PUBLIC RCL_WARN_UNUSED rcl_event_t rcl_get_zero_initialized_event(void)
Return a rcl_event_t struct with members set to NULL.
Definition: event.c:39
Versions of rosidl_typesupport_cpp::get_message_type_support_handle that handle adapted types.
RCLCPP_PUBLIC Logger get_logger(const std::string &name)
Return a named logger.
Definition: logger.cpp:34
Structure which encapsulates a ROS QoS event handle.
Definition: event.h:61
Container for subscription's, guard condition's, etc to be waited on.
Definition: wait.h:42
Contains callbacks for various types of events a Publisher can receive from the middleware.
Contains callbacks for non-message events that a Subscription can receive from the middleware.
#define RCL_RET_UNSUPPORTED
Unsupported return code.
Definition: types.h:37
#define RCL_RET_OK
Success return code.
Definition: types.h:27
rmw_ret_t rcl_ret_t
The type that holds an rcl return code.
Definition: types.h:24