diff --git a/libraries/AP_InertialSensor/AP_InertialSensor.cpp b/libraries/AP_InertialSensor/AP_InertialSensor.cpp index 1723d71901..30c6478304 100644 --- a/libraries/AP_InertialSensor/AP_InertialSensor.cpp +++ b/libraries/AP_InertialSensor/AP_InertialSensor.cpp @@ -1547,7 +1547,7 @@ void AP_InertialSensor::set_delta_angle(uint8_t instance, const Vector3f &deltaa /* * Get an AuxiliaryBus on the backend identified by @backend_id */ -AuxiliaryBus *AP_InertialSensor::get_auxiliar_bus(int16_t backend_id) +AuxiliaryBus *AP_InertialSensor::get_auxiliary_bus(int16_t backend_id) { _detect_backends(); @@ -1555,7 +1555,7 @@ AuxiliaryBus *AP_InertialSensor::get_auxiliar_bus(int16_t backend_id) if (backend == NULL) return NULL; - return backend->get_auxiliar_bus(); + return backend->get_auxiliary_bus(); } #if INS_VIBRATION_CHECK diff --git a/libraries/AP_InertialSensor/AP_InertialSensor.h b/libraries/AP_InertialSensor/AP_InertialSensor.h index 52e11eb4fd..6631b2f108 100644 --- a/libraries/AP_InertialSensor/AP_InertialSensor.h +++ b/libraries/AP_InertialSensor/AP_InertialSensor.h @@ -236,7 +236,8 @@ public: void set_delta_velocity(uint8_t instance, float deltavt, const Vector3f &deltav); void set_delta_angle(uint8_t instance, const Vector3f &deltaa); - AuxiliaryBus *get_auxiliar_bus(int16_t backend_id); + AuxiliaryBus *get_auxiliary_bus(int16_t backend_id); + AuxiliaryBus *get_auxiliar_bus(int16_t backend_id) { return get_auxiliary_bus(backend_id); } private: diff --git a/libraries/AP_InertialSensor/AP_InertialSensor_Backend.h b/libraries/AP_InertialSensor/AP_InertialSensor_Backend.h index da5c14e1cb..38857f3d9a 100644 --- a/libraries/AP_InertialSensor/AP_InertialSensor_Backend.h +++ b/libraries/AP_InertialSensor/AP_InertialSensor_Backend.h @@ -64,7 +64,7 @@ public: /* * Return an AuxiliaryBus if backend has another bus it is able to export */ - virtual AuxiliaryBus *get_auxiliar_bus() { return nullptr; } + virtual AuxiliaryBus *get_auxiliary_bus() { return nullptr; } /* return the product ID diff --git a/libraries/AP_InertialSensor/AP_InertialSensor_MPU6000.cpp b/libraries/AP_InertialSensor/AP_InertialSensor_MPU6000.cpp index 220654de6f..1a9c2deaa0 100644 --- a/libraries/AP_InertialSensor/AP_InertialSensor_MPU6000.cpp +++ b/libraries/AP_InertialSensor/AP_InertialSensor_MPU6000.cpp @@ -306,7 +306,7 @@ AP_HAL::Semaphore* AP_MPU6000_BusDriver_SPI::get_semaphore() return _spi->get_semaphore(); } -bool AP_MPU6000_BusDriver_SPI::has_auxiliar_bus() +bool AP_MPU6000_BusDriver_SPI::has_auxiliary_bus() { return true; } @@ -415,7 +415,7 @@ AP_HAL::Semaphore* AP_MPU6000_BusDriver_I2C::get_semaphore() return _i2c->get_semaphore(); } -bool AP_MPU6000_BusDriver_I2C::has_auxiliar_bus() +bool AP_MPU6000_BusDriver_I2C::has_auxiliary_bus() { return false; } @@ -459,7 +459,7 @@ AP_InertialSensor_MPU6000::AP_InertialSensor_MPU6000(AP_InertialSensor &imu, AP_ AP_InertialSensor_MPU6000::~AP_InertialSensor_MPU6000() { delete _bus; - delete _auxiliar_bus; + delete _auxiliary_bus; delete _samples; } @@ -707,15 +707,15 @@ bool AP_InertialSensor_MPU6000::update( void ) return true; } -AuxiliaryBus *AP_InertialSensor_MPU6000::get_auxiliar_bus() +AuxiliaryBus *AP_InertialSensor_MPU6000::get_auxiliary_bus() { - if (_auxiliar_bus) - return _auxiliar_bus; + if (_auxiliary_bus) + return _auxiliary_bus; - if (_bus->has_auxiliar_bus()) - _auxiliar_bus = new AP_MPU6000_AuxiliaryBus(*this); + if (_bus->has_auxiliary_bus()) + _auxiliary_bus = new AP_MPU6000_AuxiliaryBus(*this); - return _auxiliar_bus; + return _auxiliary_bus; } /*================ HARDWARE FUNCTIONS ==================== */ diff --git a/libraries/AP_InertialSensor/AP_InertialSensor_MPU6000.h b/libraries/AP_InertialSensor/AP_InertialSensor_MPU6000.h index 2383f02e85..f567624c29 100644 --- a/libraries/AP_InertialSensor/AP_InertialSensor_MPU6000.h +++ b/libraries/AP_InertialSensor/AP_InertialSensor_MPU6000.h @@ -51,7 +51,7 @@ public: AP_HAL::DigitalSource *_drdy_pin, uint8_t &n_samples) = 0; virtual AP_HAL::Semaphore* get_semaphore() = 0; - virtual bool has_auxiliar_bus() = 0; + virtual bool has_auxiliary_bus() = 0; }; class AP_InertialSensor_MPU6000 : public AP_InertialSensor_Backend @@ -79,7 +79,7 @@ public: /* * Return an AuxiliaryBus if the bus driver allows it */ - AuxiliaryBus *get_auxiliar_bus() override; + AuxiliaryBus *get_auxiliary_bus() override; void start() override; @@ -112,7 +112,7 @@ private: AP_MPU6000_BusDriver *_bus; AP_HAL::Semaphore *_bus_sem; - AP_MPU6000_AuxiliaryBus *_auxiliar_bus = nullptr; + AP_MPU6000_AuxiliaryBus *_auxiliary_bus = nullptr; static const float _gyro_scale; @@ -161,7 +161,7 @@ public: AP_HAL::DigitalSource *_drdy_pin, uint8_t &n_samples); AP_HAL::Semaphore* get_semaphore(); - bool has_auxiliar_bus() override; + bool has_auxiliary_bus() override; private: AP_HAL::SPIDeviceDriver *_spi; @@ -184,7 +184,7 @@ public: AP_HAL::DigitalSource *_drdy_pin, uint8_t &n_samples); AP_HAL::Semaphore* get_semaphore(); - bool has_auxiliar_bus() override; + bool has_auxiliary_bus() override; private: uint8_t _addr;