ArduPlane: add Airspeed to raw sensor stream rates

This commit is contained in:
Iampete1 2023-01-21 19:14:00 +00:00 committed by Andrew Tridgell
parent 9c5d071653
commit f000ab6d1b
1 changed files with 2 additions and 1 deletions

View File

@ -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,