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