Blimp: 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 29646299ef
commit 34aad934d1
1 changed files with 2 additions and 1 deletions

View File

@ -218,7 +218,7 @@ bool GCS_MAVLINK_Blimp::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_IMU3, SCALED_PRESSURE, SCALED_PRESSURE2, SCALED_PRESSURE3 and SENSOR_OFFSETS to ground station
// @Description: Stream rate of RAW_IMU, SCALED_IMU2, SCALED_IMU3, SCALED_PRESSURE, SCALED_PRESSURE2, SCALED_PRESSURE3, AIRSPEED and SENSOR_OFFSETS to ground station
// @Units: Hz
// @Range: 0 10
// @Increment: 1
@ -315,6 +315,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,