mirror of https://github.com/ArduPilot/ardupilot
AP_Airspeed: correct spelling of configured
This commit is contained in:
parent
273e0795d0
commit
4cb0a922b2
|
@ -58,7 +58,7 @@ uint8_t AP_Airspeed_Backend::get_bus(void) const
|
|||
return frontend.param[instance].bus;
|
||||
}
|
||||
|
||||
bool AP_Airspeed_Backend::bus_is_confgured(void) const
|
||||
bool AP_Airspeed_Backend::bus_is_configured(void) const
|
||||
{
|
||||
return frontend.param[instance].bus.configured();
|
||||
}
|
||||
|
|
|
@ -59,7 +59,7 @@ protected:
|
|||
int8_t get_pin(void) const;
|
||||
float get_psi_range(void) const;
|
||||
uint8_t get_bus(void) const;
|
||||
bool bus_is_confgured(void) const;
|
||||
bool bus_is_configured(void) const;
|
||||
uint8_t get_instance(void) const {
|
||||
return instance;
|
||||
}
|
||||
|
|
|
@ -62,7 +62,7 @@ bool AP_Airspeed_MS4525::probe(uint8_t bus, uint8_t address)
|
|||
bool AP_Airspeed_MS4525::init()
|
||||
{
|
||||
static const uint8_t addresses[] = { MS4525D0_I2C_ADDR1, MS4525D0_I2C_ADDR2, MS4525D0_I2C_ADDR3 };
|
||||
if (bus_is_confgured()) {
|
||||
if (bus_is_configured()) {
|
||||
// the user has configured a specific bus
|
||||
for (uint8_t addr : addresses) {
|
||||
if (probe(get_bus(), addr)) {
|
||||
|
|
Loading…
Reference in New Issue