desktop: fixed build with updated dataflash interface

This commit is contained in:
Andrew Tridgell 2011-11-13 16:48:30 +11:00 committed by Pat Hickey
parent 8245835ea3
commit e0488e134f
2 changed files with 28 additions and 33 deletions

View File

@ -185,7 +185,7 @@ else
endif
# these are library objects we don't want in the desktop build (maybe we'll add them later)
NODESKTOP := DataFlash/DataFlash_APM1.cpp FastSerial/FastSerial.cpp AP_Compass/AP_Compass_HMC5843.cpp APM_BMP085/APM_BMP085.cpp AP_IMU/AP_IMU_Oilpan.cpp AP_OpticalFlow/AP_OpticalFlow_ADNS3080.cpp
NODESKTOP := DataFlash/DataFlash_APM1.cpp FastSerial/FastSerial.cpp AP_Compass/AP_Compass_HMC5843.cpp APM_BMP085/APM_BMP085.cpp AP_IMU/AP_IMU_Oilpan.cpp AP_OpticalFlow/AP_OpticalFlow_ADNS3080.cpp AP_InertialSensor_Oilpan.cpp AP_InertialSensor/AP_InertialSensor.cpp
#
# Find sketchbook libraries referenced by the sketch.

View File

@ -18,13 +18,8 @@ static uint8_t buffer[2][DF_PAGE_SIZE];
#define OVERWRITE_DATA 1 // 0: When reach the end page stop, 1: Start overwritten from page 1
// Constructors ////////////////////////////////////////////////////////////////
DataFlash_Class::DataFlash_Class()
{
}
// Public Methods //////////////////////////////////////////////////////////////
void DataFlash_Class::Init(void)
void DataFlash_APM1::Init(void)
{
if (flash_fd == 0) {
flash_fd = open("dataflash.bin", O_RDWR, 0777);
@ -45,7 +40,7 @@ void DataFlash_Class::Init(void)
}
// This function is mainly to test the device
void DataFlash_Class::ReadManufacturerID()
void DataFlash_APM1::ReadManufacturerID()
{
df_manufacturer = 1;
df_device_0 = 2;
@ -53,55 +48,55 @@ void DataFlash_Class::ReadManufacturerID()
}
// Read the status register
byte DataFlash_Class::ReadStatusReg()
byte DataFlash_APM1::ReadStatusReg()
{
return 0;
}
// Read the status of the DataFlash
inline
byte DataFlash_Class::ReadStatus()
byte DataFlash_APM1::ReadStatus()
{
return 1;
}
inline
uint16_t DataFlash_Class::PageSize()
uint16_t DataFlash_APM1::PageSize()
{
return df_PageSize;
}
// Wait until DataFlash is in ready state...
void DataFlash_Class::WaitReady()
void DataFlash_APM1::WaitReady()
{
while(!ReadStatus());
}
void DataFlash_Class::PageToBuffer(unsigned char BufferNum, uint16_t PageAdr)
void DataFlash_APM1::PageToBuffer(unsigned char BufferNum, uint16_t PageAdr)
{
pread(flash_fd, buffer[BufferNum-1], DF_PAGE_SIZE, PageAdr*DF_PAGE_SIZE);
}
void DataFlash_Class::BufferToPage (unsigned char BufferNum, uint16_t PageAdr, unsigned char wait)
void DataFlash_APM1::BufferToPage (unsigned char BufferNum, uint16_t PageAdr, unsigned char wait)
{
pwrite(flash_fd, buffer[BufferNum-1], DF_PAGE_SIZE, PageAdr*DF_PAGE_SIZE);
}
void DataFlash_Class::BufferWrite (unsigned char BufferNum, uint16_t IntPageAdr, unsigned char Data)
void DataFlash_APM1::BufferWrite (unsigned char BufferNum, uint16_t IntPageAdr, unsigned char Data)
{
buffer[BufferNum-1][IntPageAdr] = (uint8_t)Data;
}
unsigned char DataFlash_Class::BufferRead (unsigned char BufferNum, uint16_t IntPageAdr)
unsigned char DataFlash_APM1::BufferRead (unsigned char BufferNum, uint16_t IntPageAdr)
{
return (unsigned char)buffer[BufferNum-1][IntPageAdr];
}
// *** END OF INTERNAL FUNCTIONS ***
void DataFlash_Class::PageErase (uint16_t PageAdr)
void DataFlash_APM1::PageErase (uint16_t PageAdr)
{
uint8_t fill[DF_PAGE_SIZE];
memset(fill, 0xFF, sizeof(fill));
@ -109,7 +104,7 @@ void DataFlash_Class::PageErase (uint16_t PageAdr)
}
void DataFlash_Class::ChipErase ()
void DataFlash_APM1::ChipErase ()
{
for (int i=0; DF_NUM_PAGES; i++) {
PageErase(i);
@ -117,7 +112,7 @@ void DataFlash_Class::ChipErase ()
}
// *** DATAFLASH PUBLIC FUNCTIONS ***
void DataFlash_Class::StartWrite(int16_t PageAdr)
void DataFlash_APM1::StartWrite(int16_t PageAdr)
{
df_BufferNum = 1;
df_BufferIdx = 4;
@ -130,7 +125,7 @@ void DataFlash_Class::StartWrite(int16_t PageAdr)
BufferWrite(df_BufferNum,3,df_FilePage&0xFF); // Low byte
}
void DataFlash_Class::FinishWrite(void)
void DataFlash_APM1::FinishWrite(void)
{
df_BufferIdx = 0;
BufferToPage(df_BufferNum,df_PageAdr,0); // Write Buffer to memory, NO WAIT
@ -159,7 +154,7 @@ void DataFlash_Class::FinishWrite(void)
}
void DataFlash_Class::WriteByte(byte data)
void DataFlash_APM1::WriteByte(byte data)
{
if (!df_Stop_Write)
{
@ -189,13 +184,13 @@ void DataFlash_Class::WriteByte(byte data)
}
}
void DataFlash_Class::WriteInt(int16_t data)
void DataFlash_APM1::WriteInt(int16_t data)
{
WriteByte(data>>8); // High byte
WriteByte(data&0xFF); // Low byte
}
void DataFlash_Class::WriteLong(int32_t data)
void DataFlash_APM1::WriteLong(int32_t data)
{
WriteByte(data>>24); // First byte
WriteByte(data>>16);
@ -204,18 +199,18 @@ void DataFlash_Class::WriteLong(int32_t data)
}
// Get the last page written to
int16_t DataFlash_Class::GetWritePage()
int16_t DataFlash_APM1::GetWritePage()
{
return(df_PageAdr);
}
// Get the last page read
int16_t DataFlash_Class::GetPage()
int16_t DataFlash_APM1::GetPage()
{
return(df_Read_PageAdr-1);
}
void DataFlash_Class::StartRead(int16_t PageAdr)
void DataFlash_APM1::StartRead(int16_t PageAdr)
{
df_Read_BufferNum=1;
df_Read_BufferIdx=4;
@ -225,7 +220,7 @@ void DataFlash_Class::StartRead(int16_t PageAdr)
df_Read_PageAdr++;
}
byte DataFlash_Class::ReadByte()
byte DataFlash_APM1::ReadByte()
{
byte result;
@ -246,7 +241,7 @@ byte DataFlash_Class::ReadByte()
return result;
}
int16_t DataFlash_Class::ReadInt()
int16_t DataFlash_APM1::ReadInt()
{
uint16_t result;
@ -255,7 +250,7 @@ int16_t DataFlash_Class::ReadInt()
return (int16_t)result;
}
int32_t DataFlash_Class::ReadLong()
int32_t DataFlash_APM1::ReadLong()
{
uint32_t result;
@ -266,21 +261,21 @@ int32_t DataFlash_Class::ReadLong()
return (int32_t)result;
}
void DataFlash_Class::SetFileNumber(uint16_t FileNumber)
void DataFlash_APM1::SetFileNumber(uint16_t FileNumber)
{
df_FileNumber = FileNumber;
df_FilePage = 1;
}
uint16_t DataFlash_Class::GetFileNumber()
uint16_t DataFlash_APM1::GetFileNumber()
{
return df_FileNumber;
}
uint16_t DataFlash_Class::GetFilePage()
uint16_t DataFlash_APM1::GetFilePage()
{
return df_FilePage;
}
// make one instance for the user to use
DataFlash_Class DataFlash;
DataFlash_APM1::DataFlash_APM1() {}