mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-01 13:38:38 -04:00
DataFlash_Empty defined
This commit is contained in:
parent
b7cd4312f3
commit
4c930b77a4
@ -94,5 +94,6 @@ public:
|
||||
#include "DataFlash_APM1.h"
|
||||
#include "DataFlash_APM2.h"
|
||||
#include "DataFlash_SITL.h"
|
||||
#include "DataFlash_Empty.h"
|
||||
|
||||
#endif
|
||||
|
74
libraries/DataFlash/DataFlash_Empty.cpp
Normal file
74
libraries/DataFlash/DataFlash_Empty.cpp
Normal file
@ -0,0 +1,74 @@
|
||||
/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
|
||||
/*
|
||||
hacked up DataFlash library for Desktop support
|
||||
*/
|
||||
|
||||
#include "DataFlash_Empty.h"
|
||||
#define DF_PAGE_SIZE 512
|
||||
#define DF_NUM_PAGES 4096
|
||||
|
||||
// Public Methods //////////////////////////////////////////////////////////////
|
||||
void DataFlash_Empty::Init(void)
|
||||
{
|
||||
df_PageSize = DF_PAGE_SIZE;
|
||||
// reserve last page for config information
|
||||
df_NumPages = DF_NUM_PAGES - 1;
|
||||
}
|
||||
|
||||
// This function is mainly to test the device
|
||||
void DataFlash_Empty::ReadManufacturerID()
|
||||
{
|
||||
df_manufacturer = 1;
|
||||
df_device = 0x0203;
|
||||
}
|
||||
|
||||
bool DataFlash_Empty::CardInserted(void)
|
||||
{
|
||||
return true;
|
||||
}
|
||||
|
||||
// Read the status register
|
||||
uint8_t DataFlash_Empty::ReadStatusReg()
|
||||
{
|
||||
return 0;
|
||||
}
|
||||
|
||||
// Read the status of the DataFlash
|
||||
inline
|
||||
uint8_t DataFlash_Empty::ReadStatus()
|
||||
{
|
||||
return 1;
|
||||
}
|
||||
|
||||
|
||||
inline uint16_t DataFlash_Empty::PageSize()
|
||||
{ }
|
||||
|
||||
|
||||
// Wait until DataFlash is in ready state...
|
||||
void DataFlash_Empty::WaitReady()
|
||||
{ }
|
||||
|
||||
void DataFlash_Empty::PageToBuffer(unsigned char BufferNum, uint16_t PageAdr)
|
||||
{ }
|
||||
|
||||
void DataFlash_Empty::BufferToPage (unsigned char BufferNum, uint16_t PageAdr, unsigned char wait)
|
||||
{ }
|
||||
|
||||
void DataFlash_Empty::BufferWrite (unsigned char BufferNum,
|
||||
uint16_t IntPageAdr, unsigned char Data)
|
||||
{ }
|
||||
|
||||
unsigned char DataFlash_Empty::BufferRead (unsigned char BufferNum,
|
||||
uint16_t IntPageAdr)
|
||||
{ return 0; }
|
||||
|
||||
// *** END OF INTERNAL FUNCTIONS ***
|
||||
|
||||
void DataFlash_Empty::PageErase (uint16_t PageAdr) { }
|
||||
|
||||
void DataFlash_Empty::BlockErase (uint16_t BlockAdr) { }
|
||||
|
||||
void DataFlash_Empty::ChipErase() { }
|
||||
|
||||
|
34
libraries/DataFlash/DataFlash_Empty.h
Normal file
34
libraries/DataFlash/DataFlash_Empty.h
Normal file
@ -0,0 +1,34 @@
|
||||
/* ************************************************************ */
|
||||
/* DataFlash_EMPTY Log library */
|
||||
/* ************************************************************ */
|
||||
#ifndef __DATAFLASH_EMPTY_H__
|
||||
#define __DATAFLASH_EMPTY_H__
|
||||
|
||||
#include <AP_HAL.h>
|
||||
#include "DataFlash.h"
|
||||
|
||||
class DataFlash_Empty : public DataFlash_Class
|
||||
{
|
||||
private:
|
||||
//Methods
|
||||
uint8_t BufferRead (uint8_t BufferNum, uint16_t IntPageAdr);
|
||||
void BufferWrite (uint8_t BufferNum, uint16_t IntPageAdr, uint8_t Data);
|
||||
void BufferToPage (uint8_t BufferNum, uint16_t PageAdr, uint8_t wait);
|
||||
void PageToBuffer(uint8_t BufferNum, uint16_t PageAdr);
|
||||
void WaitReady();
|
||||
uint8_t ReadStatusReg();
|
||||
uint8_t ReadStatus();
|
||||
uint16_t PageSize();
|
||||
void PageErase (uint16_t PageAdr);
|
||||
void BlockErase (uint16_t BlockAdr);
|
||||
void ChipErase();
|
||||
|
||||
public:
|
||||
|
||||
DataFlash_Empty() {}
|
||||
void Init();
|
||||
void ReadManufacturerID();
|
||||
bool CardInserted();
|
||||
};
|
||||
|
||||
#endif // __DATAFLASH_EMPTY_H__
|
Loading…
Reference in New Issue
Block a user