PX4 ROS 2 Interface Library
Library to interface with PX4 from a companion computer using ROS 2
subscription.hpp
1 /****************************************************************************
2  * Copyright (c) 2023 PX4 Development Team.
3  * SPDX-License-Identifier: BSD-3-Clause
4  ****************************************************************************/
5 
6 #pragma once
7 
8 #include <px4_ros2/common/context.hpp>
9 
10 using namespace std::chrono_literals; // NOLINT
11 
12 namespace px4_ros2
13 {
21 template<typename RosMessageType>
23 {
24  using UpdateCallback = std::function<void (const RosMessageType &)>;
25 
26 public:
27  Subscription(Context & context, const std::string & topic)
28  : _node(context.node())
29  {
30  const std::string namespaced_topic = context.topicNamespacePrefix() + topic;
31  _subscription = _node.create_subscription<RosMessageType>(
32  namespaced_topic, rclcpp::QoS(1).best_effort(),
33  [this](const typename RosMessageType::UniquePtr msg) {
34  _last = *msg;
35  _last_message_time = _node.get_clock()->now();
36  for (const auto & callback : _callbacks) {
37  callback(_last);
38  }
39  });
40  }
41 
47  void onUpdate(const UpdateCallback & callback)
48  {
49  _callbacks.push_back(callback);
50  }
51 
58  const RosMessageType & last() const
59  {
60  if (!hasReceivedMessages()) {
61  throw std::runtime_error("No messages received.");
62  }
63  return _last;
64  }
65 
71  const rclcpp::Time & lastTime() const
72  {
73  return _last_message_time;
74  }
75 
83  template<typename DurationT = std::milli>
84  bool lastValid(const std::chrono::duration<int64_t, DurationT> max_delay = 500ms) const
85  {
86  return hasReceivedMessages() && _node.get_clock()->now() - _last_message_time < max_delay;
87  }
88 
89 protected:
90  rclcpp::Node & _node;
91 
92 private:
93  typename rclcpp::Subscription<RosMessageType>::SharedPtr _subscription{nullptr};
94 
95  RosMessageType _last;
96  rclcpp::Time _last_message_time;
97 
98  std::vector<std::function<void(const RosMessageType &)>> _callbacks{};
99 
100  bool hasReceivedMessages() const
101  {
102  return _last_message_time.seconds() != 0;
103  }
104 };
105 
107 } // namespace px4_ros2
Definition: context.hpp:20
Provides a subscription to arbitrary ROS topics.
Definition: subscription.hpp:23
bool lastValid(const std::chrono::duration< int64_t, DurationT > max_delay=500ms) const
Check whether the last message is still valid. To be valid, the message must have been received withi...
Definition: subscription.hpp:84
void onUpdate(const UpdateCallback &callback)
Add a callback to execute when receiving a new message.
Definition: subscription.hpp:47
const RosMessageType & last() const
Get the last-received message.
Definition: subscription.hpp:58
const rclcpp::Time & lastTime() const
Get the receive-time of the last message.
Definition: subscription.hpp:71