From 29646299ef4070515f7313c578435d17b94baf2a Mon Sep 17 00:00:00 2001 From: Iampete1 Date: Sat, 21 Jan 2023 19:14:00 +0000 Subject: [PATCH] ArduSub: add Airspeed to raw sensor stream rates --- ArduSub/GCS_Mavlink.cpp | 3 ++- 1 file changed, 2 insertions(+), 1 deletion(-) diff --git a/ArduSub/GCS_Mavlink.cpp b/ArduSub/GCS_Mavlink.cpp index 63fb05f821..e93c99f35d 100644 --- a/ArduSub/GCS_Mavlink.cpp +++ b/ArduSub/GCS_Mavlink.cpp @@ -266,7 +266,7 @@ bool GCS_MAVLINK_Sub::try_send_message(enum ap_message id) const AP_Param::GroupInfo GCS_MAVLINK_Parameters::var_info[] = { // @Param: RAW_SENS // @DisplayName: Raw sensor stream rate - // @Description: Stream rate of RAW_IMU, SCALED_IMU2, SCALED_PRESSURE, and SENSOR_OFFSETS to ground station + // @Description: Stream rate of RAW_IMU, SCALED_IMU2, SCALED_PRESSURE, AIRSPEED, and SENSOR_OFFSETS to ground station // @Units: Hz // @Range: 0 50 // @Increment: 1 @@ -353,6 +353,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,