PX4 ROS 2 Interface Library
Library to interface with PX4 from a companion computer using ROS 2
airspeed.hpp
1 /****************************************************************************
2  * Copyright (c) 2025 PX4 Development Team.
3  * SPDX-License-Identifier: BSD-3-Clause
4  ****************************************************************************/
5 
6 #pragma once
7 
8 #include <Eigen/Eigen>
9 #include <px4_msgs/msg/airspeed_validated.hpp>
10 #include <px4_ros2/common/context.hpp>
11 #include <px4_ros2/utils/subscription.hpp>
12 
13 namespace px4_ros2
14 {
22 class OdometryAirspeed : public Subscription<px4_msgs::msg::AirspeedValidated>
23 {
24 public:
25  explicit OdometryAirspeed(Context & context);
26 
27  float indicatedAirspeed() const
28  {
29  if (!lastValid()) {
30  return NAN;
31  }
32  const px4_msgs::msg::AirspeedValidated & aspd = last();
33  return aspd.indicated_airspeed_m_s;
34  }
35 
36  float calibratedAirspeed() const
37  {
38  if (!lastValid()) {
39  return NAN;
40  }
41  const px4_msgs::msg::AirspeedValidated & aspd = last();
42  return aspd.calibrated_airspeed_m_s;
43  }
44 
45  float trueAirspeed() const
46  {
47  if (!lastValid()) {
48  return NAN;
49  }
50  const px4_msgs::msg::AirspeedValidated & aspd = last();
51  return aspd.true_airspeed_m_s;
52  }
53 };
54 
56 } /* namespace px4_ros2 */
Definition: context.hpp:20
Provides access to the vehicle's airspeed estimates.
Definition: airspeed.hpp:23
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
const px4_msgs::msg::AirspeedValidated & last() const
Get the last-received message.
Definition: subscription.hpp:58