8 #include <px4_ros2/common/context.hpp>
9 #include <px4_ros2/common/exception.hpp>
10 #include <px4_ros2/components/shared_subscription.hpp>
12 using namespace std::chrono_literals;
26 template<
typename RosMessageType>
29 using UpdateCallback = std::function<void (
const RosMessageType &)>;
33 : _node(context.node())
35 const std::string namespaced_topic = context.topicNamespacePrefix() + topic;
37 _node, namespaced_topic,
38 [
this](
const typename RosMessageType::UniquePtr & msg) {
40 _last_message_time = _node.get_clock()->now();
41 for (
const auto & callback : _callbacks) {
54 _callbacks.push_back(callback);
63 const RosMessageType &
last()
const
65 if (!hasReceivedMessages()) {
78 return _last_message_time;
88 template<
typename DurationT = std::milli>
89 bool lastValid(
const std::chrono::duration<int64_t, DurationT> max_delay = 500ms)
const
91 return hasReceivedMessages() && _node.get_clock()->now() - _last_message_time < max_delay;
98 SharedSubscriptionCallbackInstance _callback_instance;
100 RosMessageType _last;
101 rclcpp::Time _last_message_time;
103 std::vector<std::function<void(
const RosMessageType &)>> _callbacks{};
105 bool hasReceivedMessages()
const
107 return _last_message_time.seconds() != 0;
Shared class for a ROS subscription.
Definition: shared_subscription.hpp:40
Definition: context.hpp:20
Definition: exception.hpp:16
Provides a subscription to arbitrary ROS topics.
Definition: subscription.hpp:28
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:89
void onUpdate(const UpdateCallback &callback)
Add a callback to execute when receiving a new message.
Definition: subscription.hpp:52
const RosMessageType & last() const
Get the last-received message.
Definition: subscription.hpp:63
const rclcpp::Time & lastTime() const
Get the receive-time of the last message.
Definition: subscription.hpp:76