diff --git a/libraries/AP_HAL_AVR/HAL_AVR_APM1_Class.cpp b/libraries/AP_HAL_AVR/HAL_AVR_APM1_Class.cpp index ec0b74a176..c376f46b79 100644 --- a/libraries/AP_HAL_AVR/HAL_AVR_APM1_Class.cpp +++ b/libraries/AP_HAL_AVR/HAL_AVR_APM1_Class.cpp @@ -21,7 +21,8 @@ AVRUARTDriverInstance(avrUart0Driver, 0); AVRUARTDriverInstance(avrUart1Driver, 1); AVRUARTDriverInstance(avrUart3Driver, 3); -static AVRI2CDriver avrI2CDriver; +static AVRSemaphore i2cSemaphore; +static AVRI2CDriver avrI2CDriver(&i2cSemaphore); static APM1SPIDeviceManager apm1SPIDriver; static AVRAnalogIn avrAnalogIn; static AVREEPROMStorage avrEEPROMStorage; diff --git a/libraries/AP_HAL_AVR/HAL_AVR_APM2_Class.cpp b/libraries/AP_HAL_AVR/HAL_AVR_APM2_Class.cpp index e739ae33f4..9d43541994 100644 --- a/libraries/AP_HAL_AVR/HAL_AVR_APM2_Class.cpp +++ b/libraries/AP_HAL_AVR/HAL_AVR_APM2_Class.cpp @@ -21,7 +21,8 @@ AVRUARTDriverInstance(avrUart0Driver, 0); AVRUARTDriverInstance(avrUart1Driver, 1); AVRUARTDriverInstance(avrUart2Driver, 2); -static AVRI2CDriver avrI2CDriver; +static AVRSemaphore i2cSemaphore; +static AVRI2CDriver avrI2CDriver(&i2cSemaphore); static APM2SPIDeviceManager apm2SPIDriver; static AVRAnalogIn avrAnalogIn; static AVREEPROMStorage avrEEPROMStorage; diff --git a/libraries/AP_HAL_AVR/I2CDriver.cpp b/libraries/AP_HAL_AVR/I2CDriver.cpp index f289074fd1..66cb0b0d05 100644 --- a/libraries/AP_HAL_AVR/I2CDriver.cpp +++ b/libraries/AP_HAL_AVR/I2CDriver.cpp @@ -316,5 +316,4 @@ SIGNAL(TWI_vect) } } - #endif diff --git a/libraries/AP_HAL_AVR/I2CDriver.h b/libraries/AP_HAL_AVR/I2CDriver.h index 91947c4c05..53b9aeac5a 100644 --- a/libraries/AP_HAL_AVR/I2CDriver.h +++ b/libraries/AP_HAL_AVR/I2CDriver.h @@ -9,7 +9,7 @@ class AP_HAL_AVR::AVRI2CDriver : public AP_HAL::I2CDriver { public: - AVRI2CDriver() {} + AVRI2CDriver(AP_HAL::Semaphore *sem) : _sem(sem) {} void begin(); void end(); @@ -26,6 +26,8 @@ public: uint8_t len, uint8_t* data); uint8_t lockup_count() { return _lockup_count; } + AP_HAL::Semaphore* get_semaphore() { return _sem; } + private: uint8_t _start(); uint8_t _stop(); @@ -39,6 +41,8 @@ private: uint8_t _lockup_count; uint16_t _timeoutDelay; + + AP_HAL::Semaphore *_sem; }; #endif // __AP_HAL_AVR_I2C_DRIVER_H__