diff --git a/libraries/DataFlash/DataFlash_APM2.cpp b/libraries/DataFlash/DataFlash_APM2.cpp index f9cba3a0674ef311b621ab73f3f769a1281178d3..d38f2cdba0f1c695046fd458e0a423f128fb8c89 100644 --- a/libraries/DataFlash/DataFlash_APM2.cpp +++ b/libraries/DataFlash/DataFlash_APM2.cpp @@ -97,8 +97,8 @@ unsigned char DataFlash_APM2::SPI_transfer(unsigned char data) // get spi3 semaphore if required. if failed to get semaphore then // just quietly fail - if ( _semaphore != NULL) { - if( !_semaphore->get(this) ) { + if ( _spi3_semaphore != NULL) { + if( !_spi3_semaphore->get(this) ) { return 0; } } @@ -113,8 +113,8 @@ unsigned char DataFlash_APM2::SPI_transfer(unsigned char data) retval = UDR3; // release spi3 semaphore - if ( _semaphore != NULL) { - _semaphore->release(this); + if ( _spi3_semaphore != NULL) { + _spi3_semaphore->release(this); } return retval; diff --git a/libraries/DataFlash/DataFlash_APM2.h b/libraries/DataFlash/DataFlash_APM2.h index 43ee446c24146ff0aa2531a68589431a49648e61..37efe0178ef002814c7f505f9f8556a58b581324 100644 --- a/libraries/DataFlash/DataFlash_APM2.h +++ b/libraries/DataFlash/DataFlash_APM2.h @@ -27,9 +27,9 @@ private: void BlockErase (uint16_t BlockAdr); void ChipErase(void (*delay_cb)(unsigned long)); - AP_Semaphore* _semaphore; + AP_Semaphore* _spi3_semaphore; public: - DataFlash_APM2(AP_Semaphore* semaphore = NULL) : _semaphore(semaphore) {} + DataFlash_APM2(AP_Semaphore* spi3_semaphore = NULL) : _spi3_semaphore(spi3_semaphore) {} void Init(); void ReadManufacturerID();