diff --git a/libraries/AP_AHRS/AP_AHRS.cpp b/libraries/AP_AHRS/AP_AHRS.cpp index 4780b75043a730..b4e08ea955fce6 100644 --- a/libraries/AP_AHRS/AP_AHRS.cpp +++ b/libraries/AP_AHRS/AP_AHRS.cpp @@ -3170,7 +3170,7 @@ uint8_t AP_AHRS::get_active_airspeed_index() const #if HAL_NAVEKF3_AVAILABLE if (active_EKF_type() == EKFType::THREE) { uint8_t ret = EKF3.getActiveAirspeed(); - if (ret != 255 && airspeed->healthy(ret) && airspeed->use(ret)) { + if (ret != UINT8_MAX && airspeed->healthy(ret) && airspeed->use(ret)) { return ret; } } diff --git a/libraries/AP_NavEKF3/AP_NavEKF3.cpp b/libraries/AP_NavEKF3/AP_NavEKF3.cpp index 26bbeffc23d5e8..fef08de424c792 100644 --- a/libraries/AP_NavEKF3/AP_NavEKF3.cpp +++ b/libraries/AP_NavEKF3/AP_NavEKF3.cpp @@ -1331,7 +1331,7 @@ uint8_t NavEKF3::getActiveAirspeed() const if (core) { return core[primary].getActiveAirspeed(); } else { - return 255; + return UINT8_MAX; } }