From f000ab6d1b40ace796454c69fd996d22fbe6579d Mon Sep 17 00:00:00 2001 From: Iampete1 Date: Sat, 21 Jan 2023 19:14:00 +0000 Subject: [PATCH] ArduPlane: add Airspeed to raw sensor stream rates --- ArduPlane/GCS_Mavlink.cpp | 3 ++- 1 file changed, 2 insertions(+), 1 deletion(-) diff --git a/ArduPlane/GCS_Mavlink.cpp b/ArduPlane/GCS_Mavlink.cpp index 887599d6b9..cfd7b7a71a 100644 --- a/ArduPlane/GCS_Mavlink.cpp +++ b/ArduPlane/GCS_Mavlink.cpp @@ -508,7 +508,7 @@ void GCS_MAVLINK_Plane::send_hygrometer() const AP_Param::GroupInfo GCS_MAVLINK_Parameters::var_info[] = { // @Param: RAW_SENS // @DisplayName: Raw sensor stream rate - // @Description: MAVLink Stream rate of RAW_IMU, SCALED_IMU2, SCALED_IMU3, SCALED_PRESSURE, SCALED_PRESSURE2, and SCALED_PRESSURE3 + // @Description: MAVLink Stream rate of RAW_IMU, SCALED_IMU2, SCALED_IMU3, SCALED_PRESSURE, SCALED_PRESSURE2, SCALED_PRESSURE3 and AIRSPEED // @Units: Hz // @Range: 0 50 // @Increment: 1 @@ -614,6 +614,7 @@ static const ap_message STREAM_RAW_SENSORS_msgs[] = { MSG_SCALED_PRESSURE, MSG_SCALED_PRESSURE2, MSG_SCALED_PRESSURE3, + MSG_AIRSPEED, }; static const ap_message STREAM_EXTENDED_STATUS_msgs[] = { MSG_SYS_STATUS,