AP_Airspeed: review updates

Co-authored-by: Peter Barker <pb-gh@barker.dropbear.id.au>
This commit is contained in:
Andrew Tridgell 2021-07-10 16:45:07 +10:00
parent 70bb470eb0
commit 5f87335325
2 changed files with 3 additions and 3 deletions

View File

@ -167,8 +167,8 @@ const AP_Param::GroupInfo AP_Airspeed::var_info[] = {
#ifndef HAL_BUILD_AP_PERIPH
// @Param: _OPTIONS
// @DisplayName: Airspeed options bitmask
// @Description: Bitmask of options to use with airspeed. Disable and/or re-enable sensor based on the difference between airspeed and ground speed based on ARSPD_WIND_MAX threshold, if set
// @Bitmask: 0:Disable sensor, 1:Re-enable sensor, 2:DisableVoltageCorrection
// @Description: Bitmask of options to use with airspeed. 0:Disable use based on airspeed/groundspeed mismatch (see ARSPD_WIND_MAX), 1:Automatically reenable use based on airspeed/groundspeed mismatch recovery (see ARSPD_WIND_MAX) 2:Disable voltage correction
// @Bitmask: 0:SpeedMismatchDisable, 1:AllowSpeedMismatchRecovery, 2:DisableVoltageCorrection
// @User: Advanced
AP_GROUPINFO("_OPTIONS", 21, AP_Airspeed, _options, OPTIONS_DEFAULT),

View File

@ -59,7 +59,7 @@ bool AP_Airspeed_MS4525::probe(uint8_t bus, uint8_t address)
// probe and initialise the sensor
bool AP_Airspeed_MS4525::init()
{
const uint8_t addresses[] = { MS4525D0_I2C_ADDR1, MS4525D0_I2C_ADDR2, MS4525D0_I2C_ADDR3 };
static const uint8_t addresses[] = { MS4525D0_I2C_ADDR1, MS4525D0_I2C_ADDR2, MS4525D0_I2C_ADDR3 };
if (bus_is_confgured()) {
// the user has configured a specific bus
for (uint8_t addr : addresses) {