8 #include <px4_ros2/common/context.hpp>
10 using namespace std::chrono_literals;
21 template<
typename RosMessageType>
24 using UpdateCallback = std::function<void (
const RosMessageType &)>;
28 : _node(context.node())
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) {
35 _last_message_time = _node.get_clock()->now();
36 for (
const auto & callback : _callbacks) {
49 _callbacks.push_back(callback);
58 const RosMessageType &
last()
const
60 if (!hasReceivedMessages()) {
61 throw std::runtime_error(
"No messages received.");
73 return _last_message_time;
83 template<
typename DurationT = std::milli>
84 bool lastValid(
const std::chrono::duration<int64_t, DurationT> max_delay = 500ms)
const
86 return hasReceivedMessages() && _node.get_clock()->now() - _last_message_time < max_delay;
93 typename rclcpp::Subscription<RosMessageType>::SharedPtr _subscription{
nullptr};
96 rclcpp::Time _last_message_time;
98 std::vector<std::function<void(
const RosMessageType &)>> _callbacks{};
100 bool hasReceivedMessages()
const
102 return _last_message_time.seconds() != 0;
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