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 {
21 class OdometryAirspeed : public Subscription<px4_msgs::msg::AirspeedValidated> {
22  public:
23  explicit OdometryAirspeed(Context& context);
24 
25  float indicatedAirspeed() const
26  {
27  if (!lastValid()) {
28  return NAN;
29  }
30  const px4_msgs::msg::AirspeedValidated& aspd = last();
31  return aspd.indicated_airspeed_m_s;
32  }
33 
34  float calibratedAirspeed() const
35  {
36  if (!lastValid()) {
37  return NAN;
38  }
39  const px4_msgs::msg::AirspeedValidated& aspd = last();
40  return aspd.calibrated_airspeed_m_s;
41  }
42 
43  float trueAirspeed() const
44  {
45  if (!lastValid()) {
46  return NAN;
47  }
48  const px4_msgs::msg::AirspeedValidated& aspd = last();
49  return aspd.true_airspeed_m_s;
50  }
51 };
52 
54 } /* namespace px4_ros2 */
Definition: context.hpp:18
Provides access to the vehicle's airspeed estimates.
Definition: airspeed.hpp:21
Provides a subscription to arbitrary ROS topics.
Definition: subscription.hpp:27
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:80
const px4_msgs::msg::AirspeedValidated & last() const
Get the last-received message.
Definition: subscription.hpp:57