DataFlash_APM2: private AP_Semaphore* rather than use extern AP_Semaphore_spi3

The AP_Semaphore* argument to the constructor can be null (and is by
default for compatibility). Semaphore is only used when non-null.
This commit is contained in:
Pat Hickey 2012-10-09 11:38:52 -07:00
parent 39be6be363
commit 00243e3c6c
2 changed files with 13 additions and 11 deletions

View File

@ -95,9 +95,12 @@ unsigned char DataFlash_APM2::SPI_transfer(unsigned char data)
{
unsigned char retval;
// get spi3 semaphore if required. if failed to get semaphore then just quietly fail
if( !AP_Semaphore_spi3.get(this) ) {
return 0;
// get spi3 semaphore if required. if failed to get semaphore then
// just quietly fail
if ( _semaphore != NULL) {
if( !_semaphore->get(this) ) {
return 0;
}
}
/* Wait for empty transmit buffer */
@ -110,7 +113,9 @@ unsigned char DataFlash_APM2::SPI_transfer(unsigned char data)
retval = UDR3;
// release spi3 semaphore
AP_Semaphore_spi3.release(this);
if ( _semaphore != NULL) {
_semaphore->release(this);
}
return retval;
}
@ -127,11 +132,6 @@ void DataFlash_APM2::CS_active()
digitalWrite(DF_SLAVESELECT,LOW);
}
// Constructors ////////////////////////////////////////////////////////////////
DataFlash_APM2::DataFlash_APM2()
{
}
// Public Methods //////////////////////////////////////////////////////////////
void DataFlash_APM2::Init(void)
{

View File

@ -4,7 +4,7 @@
#ifndef __DATAFLASH_APM2_H__
#define __DATAFLASH_APM2_H__
#include <AP_Semaphore.h> // for removing conflict with dataflash on SPI3 bus
#include <AP_Semaphore.h>
#include "DataFlash.h"
class DataFlash_APM2 : public DataFlash_Class
@ -27,8 +27,10 @@ private:
void BlockErase (uint16_t BlockAdr);
void ChipErase(void (*delay_cb)(unsigned long));
AP_Semaphore* _semaphore;
public:
DataFlash_APM2(); // Constructor
DataFlash_APM2(AP_Semaphore* semaphore = NULL) : _semaphore(semaphore) {}
void Init();
void ReadManufacturerID();
bool CardInserted();