Browse Source

DataFlash_APM2: renamed semaphore to spi3_semaphore to make it more obvious which semaphore is required.

master
rmackay9 12 years ago
parent
commit
785d9ca6a7
  1. 8
      libraries/DataFlash/DataFlash_APM2.cpp
  2. 4
      libraries/DataFlash/DataFlash_APM2.h

8
libraries/DataFlash/DataFlash_APM2.cpp

@ -97,8 +97,8 @@ unsigned char DataFlash_APM2::SPI_transfer(unsigned char data) @@ -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) @@ -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;

4
libraries/DataFlash/DataFlash_APM2.h

@ -27,9 +27,9 @@ private: @@ -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();

Loading…
Cancel
Save