ardupilot/libraries/DataFlash/DataFlash_APM2.h
Pat Hickey 00243e3c6c 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.
2012-10-09 11:38:52 -07:00

40 lines
1.5 KiB
C++

/* ************************************************************ */
/* DataFlash_APM2 Log library */
/* ************************************************************ */
#ifndef __DATAFLASH_APM2_H__
#define __DATAFLASH_APM2_H__
#include <AP_Semaphore.h>
#include "DataFlash.h"
class DataFlash_APM2 : public DataFlash_Class
{
private:
//Methods
unsigned char BufferRead (unsigned char BufferNum, uint16_t IntPageAdr);
void BufferWrite (unsigned char BufferNum, uint16_t IntPageAdr, unsigned char Data);
void BufferToPage (unsigned char BufferNum, uint16_t PageAdr, unsigned char wait);
void PageToBuffer(unsigned char BufferNum, uint16_t PageAdr);
void WaitReady();
unsigned char ReadStatusReg();
unsigned char ReadStatus();
uint16_t PageSize();
unsigned char SPI_transfer(unsigned char data);
void CS_inactive();
void CS_active();
void PageErase (uint16_t PageAdr);
void BlockErase (uint16_t BlockAdr);
void ChipErase(void (*delay_cb)(unsigned long));
AP_Semaphore* _semaphore;
public:
DataFlash_APM2(AP_Semaphore* semaphore = NULL) : _semaphore(semaphore) {}
void Init();
void ReadManufacturerID();
bool CardInserted();
};
#endif