diff --git a/libraries/AP_Airspeed/AP_Airspeed.cpp b/libraries/AP_Airspeed/AP_Airspeed.cpp index b05bba0808..80baefc4a0 100644 --- a/libraries/AP_Airspeed/AP_Airspeed.cpp +++ b/libraries/AP_Airspeed/AP_Airspeed.cpp @@ -170,8 +170,9 @@ const AP_Param::GroupInfo AP_Airspeed::var_info[] = { #ifndef HAL_BUILD_AP_PERIPH // @Param: _BUS // @DisplayName: Airspeed I2C bus - // @Description: Bus number of the I2C bus where the airspeed sensor is connected - // @Values: 0:Bus0(internal),1:Bus1(external),2:Bus2(auxiliary) + // @Description: Bus number of the I2C bus where the airspeed sensor is connected. May not correspond to board's I2C bus number labels. Retry another bus and reboot if airspeed sensor fails to initialize. + // @Values: 0:Bus0,1:Bus1,2:Bus2 + // @RebootRequired: True // @User: Advanced AP_GROUPINFO("_BUS", 9, AP_Airspeed, param[0].bus, HAL_AIRSPEED_BUS_DEFAULT), #endif // HAL_BUILD_AP_PERIPH @@ -285,8 +286,9 @@ const AP_Param::GroupInfo AP_Airspeed::var_info[] = { // @Param: 2_BUS // @DisplayName: Airspeed I2C bus for 2nd sensor - // @Description: The bus number of the I2C bus to look for the sensor on - // @Values: 0:Bus0(internal),1:Bus1(external),2:Bus2(auxiliary) + // @Description: Bus number of the I2C bus where the airspeed sensor is connected. May not correspond to board's I2C bus number labels. Retry another bus and reboot if airspeed sensor fails to initialize. + // @Values: 0:Bus0,1:Bus1,2:Bus2 + // @RebootRequired: True // @User: Advanced AP_GROUPINFO("2_BUS", 20, AP_Airspeed, param[1].bus, 1),