mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-22 16:48:29 -04:00
DataFlash_APM2: renamed semaphore to spi3_semaphore to make it more obvious which semaphore is required.
This commit is contained in:
parent
890bed4918
commit
5f2c900797
@ -97,8 +97,8 @@ unsigned char DataFlash_APM2::SPI_transfer(unsigned char data)
|
|||||||
|
|
||||||
// get spi3 semaphore if required. if failed to get semaphore then
|
// get spi3 semaphore if required. if failed to get semaphore then
|
||||||
// just quietly fail
|
// just quietly fail
|
||||||
if ( _semaphore != NULL) {
|
if ( _spi3_semaphore != NULL) {
|
||||||
if( !_semaphore->get(this) ) {
|
if( !_spi3_semaphore->get(this) ) {
|
||||||
return 0;
|
return 0;
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
@ -113,8 +113,8 @@ unsigned char DataFlash_APM2::SPI_transfer(unsigned char data)
|
|||||||
retval = UDR3;
|
retval = UDR3;
|
||||||
|
|
||||||
// release spi3 semaphore
|
// release spi3 semaphore
|
||||||
if ( _semaphore != NULL) {
|
if ( _spi3_semaphore != NULL) {
|
||||||
_semaphore->release(this);
|
_spi3_semaphore->release(this);
|
||||||
}
|
}
|
||||||
|
|
||||||
return retval;
|
return retval;
|
||||||
|
@ -27,9 +27,9 @@ private:
|
|||||||
void BlockErase (uint16_t BlockAdr);
|
void BlockErase (uint16_t BlockAdr);
|
||||||
void ChipErase(void (*delay_cb)(unsigned long));
|
void ChipErase(void (*delay_cb)(unsigned long));
|
||||||
|
|
||||||
AP_Semaphore* _semaphore;
|
AP_Semaphore* _spi3_semaphore;
|
||||||
public:
|
public:
|
||||||
DataFlash_APM2(AP_Semaphore* semaphore = NULL) : _semaphore(semaphore) {}
|
DataFlash_APM2(AP_Semaphore* spi3_semaphore = NULL) : _spi3_semaphore(spi3_semaphore) {}
|
||||||
|
|
||||||
void Init();
|
void Init();
|
||||||
void ReadManufacturerID();
|
void ReadManufacturerID();
|
||||||
|
Loading…
Reference in New Issue
Block a user