mirror of https://github.com/ArduPilot/ardupilot
dataflash: fixed datatypes to be compatible with desktop build
This commit is contained in:
parent
da50903649
commit
01cd9cc6d6
|
@ -26,7 +26,7 @@ class DataFlash_Class
|
|||
virtual void WriteLong(int32_t data) = 0;
|
||||
|
||||
// Read methods
|
||||
virtual void StartRead(int PageAdr) = 0;
|
||||
virtual void StartRead(int16_t PageAdr) = 0;
|
||||
virtual unsigned char ReadByte() = 0;
|
||||
virtual int16_t ReadInt() = 0;
|
||||
virtual int32_t ReadLong() = 0;
|
||||
|
|
|
@ -124,7 +124,7 @@ byte DataFlash_APM1::ReadStatus()
|
|||
|
||||
|
||||
inline
|
||||
unsigned int DataFlash_APM1::PageSize()
|
||||
uint16_t DataFlash_APM1::PageSize()
|
||||
{
|
||||
return(528-((ReadStatusReg()&0x01)<<4)); // if first bit 1 trhen 512 else 528 bytes
|
||||
}
|
||||
|
@ -136,7 +136,7 @@ void DataFlash_APM1::WaitReady()
|
|||
while(!ReadStatus());
|
||||
}
|
||||
|
||||
void DataFlash_APM1::PageToBuffer(unsigned char BufferNum, unsigned int PageAdr)
|
||||
void DataFlash_APM1::PageToBuffer(unsigned char BufferNum, uint16_t PageAdr)
|
||||
{
|
||||
dataflash_CS_active(); // activate dataflash command decoder
|
||||
|
||||
|
@ -163,7 +163,7 @@ void DataFlash_APM1::PageToBuffer(unsigned char BufferNum, unsigned int PageAdr)
|
|||
|
||||
}
|
||||
|
||||
void DataFlash_APM1::BufferToPage (unsigned char BufferNum, unsigned int PageAdr, unsigned char wait)
|
||||
void DataFlash_APM1::BufferToPage (unsigned char BufferNum, uint16_t PageAdr, unsigned char wait)
|
||||
{
|
||||
dataflash_CS_active(); // activate dataflash command decoder
|
||||
|
||||
|
@ -191,7 +191,7 @@ void DataFlash_APM1::BufferToPage (unsigned char BufferNum, unsigned int PageAdr
|
|||
dataflash_CS_inactive(); //deactivate dataflash command decoder
|
||||
}
|
||||
|
||||
void DataFlash_APM1::BufferWrite (unsigned char BufferNum, unsigned int IntPageAdr, unsigned char Data)
|
||||
void DataFlash_APM1::BufferWrite (unsigned char BufferNum, uint16_t IntPageAdr, unsigned char Data)
|
||||
{
|
||||
dataflash_CS_active(); // activate dataflash command decoder
|
||||
|
||||
|
@ -207,7 +207,7 @@ void DataFlash_APM1::BufferWrite (unsigned char BufferNum, unsigned int IntPageA
|
|||
dataflash_CS_inactive(); // disable dataflash command decoder
|
||||
}
|
||||
|
||||
unsigned char DataFlash_APM1::BufferRead (unsigned char BufferNum, unsigned int IntPageAdr)
|
||||
unsigned char DataFlash_APM1::BufferRead (unsigned char BufferNum, uint16_t IntPageAdr)
|
||||
{
|
||||
byte tmp;
|
||||
|
||||
|
@ -229,7 +229,7 @@ unsigned char DataFlash_APM1::BufferRead (unsigned char BufferNum, unsigned int
|
|||
}
|
||||
// *** END OF INTERNAL FUNCTIONS ***
|
||||
|
||||
void DataFlash_APM1::PageErase (unsigned int PageAdr)
|
||||
void DataFlash_APM1::PageErase (uint16_t PageAdr)
|
||||
{
|
||||
dataflash_CS_active(); // activate dataflash command decoder
|
||||
SPI.transfer(DF_PAGE_ERASE); // Command
|
||||
|
@ -269,7 +269,7 @@ void DataFlash_APM1::ChipErase ()
|
|||
}
|
||||
|
||||
// *** DATAFLASH PUBLIC FUNCTIONS ***
|
||||
void DataFlash_APM1::StartWrite(int PageAdr)
|
||||
void DataFlash_APM1::StartWrite(int16_t PageAdr)
|
||||
{
|
||||
df_BufferNum=1;
|
||||
df_BufferIdx=4;
|
||||
|
@ -342,13 +342,13 @@ void DataFlash_APM1::WriteByte(byte data)
|
|||
}
|
||||
}
|
||||
|
||||
void DataFlash_APM1::WriteInt(int data)
|
||||
void DataFlash_APM1::WriteInt(int16_t data)
|
||||
{
|
||||
WriteByte(data>>8); // High byte
|
||||
WriteByte(data&0xFF); // Low byte
|
||||
}
|
||||
|
||||
void DataFlash_APM1::WriteLong(long data)
|
||||
void DataFlash_APM1::WriteLong(int32_t data)
|
||||
{
|
||||
WriteByte(data>>24); // First byte
|
||||
WriteByte(data>>16);
|
||||
|
@ -357,18 +357,18 @@ void DataFlash_APM1::WriteLong(long data)
|
|||
}
|
||||
|
||||
// Get the last page written to
|
||||
int DataFlash_APM1::GetWritePage()
|
||||
int16_t DataFlash_APM1::GetWritePage()
|
||||
{
|
||||
return(df_PageAdr);
|
||||
}
|
||||
|
||||
// Get the last page read
|
||||
int DataFlash_APM1::GetPage()
|
||||
int16_t DataFlash_APM1::GetPage()
|
||||
{
|
||||
return(df_Read_PageAdr-1);
|
||||
}
|
||||
|
||||
void DataFlash_APM1::StartRead(int PageAdr)
|
||||
void DataFlash_APM1::StartRead(int16_t PageAdr)
|
||||
{
|
||||
df_Read_BufferNum=1;
|
||||
df_Read_BufferIdx=4;
|
||||
|
@ -412,24 +412,24 @@ byte DataFlash_APM1::ReadByte()
|
|||
return result;
|
||||
}
|
||||
|
||||
int DataFlash_APM1::ReadInt()
|
||||
int16_t DataFlash_APM1::ReadInt()
|
||||
{
|
||||
int result;
|
||||
uint16_t result;
|
||||
|
||||
result = ReadByte(); // High byte
|
||||
result = (result<<8) | ReadByte(); // Low byte
|
||||
return result;
|
||||
return (int16_t)result;
|
||||
}
|
||||
|
||||
long DataFlash_APM1::ReadLong()
|
||||
int32_t DataFlash_APM1::ReadLong()
|
||||
{
|
||||
long result;
|
||||
uint32_t result;
|
||||
|
||||
result = ReadByte(); // First byte
|
||||
result = (result<<8) | ReadByte();
|
||||
result = (result<<8) | ReadByte();
|
||||
result = (result<<8) | ReadByte(); // Last byte
|
||||
return result;
|
||||
return (int32_t)result;
|
||||
}
|
||||
|
||||
void DataFlash_APM1::SetFileNumber(uint16_t FileNumber)
|
||||
|
|
|
@ -34,7 +34,7 @@ class DataFlash_APM1 : public DataFlash_Class
|
|||
unsigned char df_manufacturer;
|
||||
unsigned char df_device_0;
|
||||
unsigned char df_device_1;
|
||||
unsigned int df_PageSize;
|
||||
uint16_t df_PageSize;
|
||||
|
||||
DataFlash_APM1(); // Constructor
|
||||
void Init();
|
||||
|
@ -51,7 +51,7 @@ class DataFlash_APM1 : public DataFlash_Class
|
|||
void WriteLong(int32_t data);
|
||||
|
||||
// Read methods
|
||||
void StartRead(int PageAdr);
|
||||
void StartRead(int16_t PageAdr);
|
||||
unsigned char ReadByte();
|
||||
int16_t ReadInt();
|
||||
int32_t ReadLong();
|
||||
|
|
|
@ -153,9 +153,9 @@ void DataFlash_Purple::ReadManufacturerID()
|
|||
}
|
||||
|
||||
// This function return 1 if Card is inserted on SD slot
|
||||
int DataFlash_Purple::CardInserted()
|
||||
bool DataFlash_Purple::CardInserted()
|
||||
{
|
||||
return (!digitalRead(DF_CARDDETECT));
|
||||
return (digitalRead(DF_CARDDETECT) != 0);
|
||||
}
|
||||
|
||||
// Read the status register
|
||||
|
@ -178,7 +178,7 @@ byte DataFlash_Purple::ReadStatus()
|
|||
|
||||
|
||||
inline
|
||||
unsigned int DataFlash_Purple::PageSize()
|
||||
uint16_t DataFlash_Purple::PageSize()
|
||||
{
|
||||
return(528-((ReadStatusReg()&0x01)<<4)); // if first bit 1 trhen 512 else 528 bytes
|
||||
}
|
||||
|
@ -190,7 +190,7 @@ void DataFlash_Purple::WaitReady()
|
|||
while(!ReadStatus());
|
||||
}
|
||||
|
||||
void DataFlash_Purple::PageToBuffer(unsigned char BufferNum, unsigned int PageAdr)
|
||||
void DataFlash_Purple::PageToBuffer(unsigned char BufferNum, uint16_t PageAdr)
|
||||
{
|
||||
CS_inactive();
|
||||
CS_active();
|
||||
|
@ -214,7 +214,7 @@ void DataFlash_Purple::PageToBuffer(unsigned char BufferNum, unsigned int PageAd
|
|||
while(!ReadStatus()); //monitor the status register, wait until busy-flag is high
|
||||
}
|
||||
|
||||
void DataFlash_Purple::BufferToPage (unsigned char BufferNum, unsigned int PageAdr, unsigned char wait)
|
||||
void DataFlash_Purple::BufferToPage (unsigned char BufferNum, uint16_t PageAdr, unsigned char wait)
|
||||
{
|
||||
CS_inactive(); // Reset dataflash command decoder
|
||||
CS_active();
|
||||
|
@ -241,7 +241,7 @@ void DataFlash_Purple::BufferToPage (unsigned char BufferNum, unsigned int PageA
|
|||
while(!ReadStatus()); //monitor the status register, wait until busy-flag is high
|
||||
}
|
||||
|
||||
void DataFlash_Purple::BufferWrite (unsigned char BufferNum, unsigned int IntPageAdr, unsigned char Data)
|
||||
void DataFlash_Purple::BufferWrite (unsigned char BufferNum, uint16_t IntPageAdr, unsigned char Data)
|
||||
{
|
||||
CS_inactive(); // Reset dataflash command decoder
|
||||
CS_active();
|
||||
|
@ -256,7 +256,7 @@ void DataFlash_Purple::BufferWrite (unsigned char BufferNum, unsigned int IntPag
|
|||
SPI_transfer(Data); //write data byte
|
||||
}
|
||||
|
||||
unsigned char DataFlash_Purple::BufferRead (unsigned char BufferNum, unsigned int IntPageAdr)
|
||||
unsigned char DataFlash_Purple::BufferRead (unsigned char BufferNum, uint16_t IntPageAdr)
|
||||
{
|
||||
byte tmp;
|
||||
|
||||
|
@ -277,7 +277,7 @@ unsigned char DataFlash_Purple::BufferRead (unsigned char BufferNum, unsigned in
|
|||
}
|
||||
// *** END OF INTERNAL FUNCTIONS ***
|
||||
|
||||
void DataFlash_Purple::PageErase (unsigned int PageAdr)
|
||||
void DataFlash_Purple::PageErase (uint16_t PageAdr)
|
||||
{
|
||||
CS_inactive(); //make sure to toggle CS signal in order
|
||||
CS_active(); //to reset Dataflash command decoder
|
||||
|
@ -314,7 +314,7 @@ void DataFlash_Purple::ChipErase ()
|
|||
}
|
||||
|
||||
// *** DATAFLASH PUBLIC FUNCTIONS ***
|
||||
void DataFlash_Purple::StartWrite(int PageAdr)
|
||||
void DataFlash_Purple::StartWrite(int16_t PageAdr)
|
||||
{
|
||||
df_BufferNum=1;
|
||||
df_BufferIdx=0;
|
||||
|
@ -376,13 +376,13 @@ void DataFlash_Purple::WriteByte(byte data)
|
|||
}
|
||||
}
|
||||
|
||||
void DataFlash_Purple::WriteInt(int data)
|
||||
void DataFlash_Purple::WriteInt(int16_t data)
|
||||
{
|
||||
WriteByte(data>>8); // High byte
|
||||
WriteByte(data&0xFF); // Low byte
|
||||
}
|
||||
|
||||
void DataFlash_Purple::WriteLong(long data)
|
||||
void DataFlash_Purple::WriteLong(int32_t data)
|
||||
{
|
||||
WriteByte(data>>24); // First byte
|
||||
WriteByte(data>>16);
|
||||
|
@ -391,18 +391,18 @@ void DataFlash_Purple::WriteLong(long data)
|
|||
}
|
||||
|
||||
// Get the last page written to
|
||||
int DataFlash_Purple::GetWritePage()
|
||||
int16_t DataFlash_Purple::GetWritePage()
|
||||
{
|
||||
return(df_PageAdr);
|
||||
}
|
||||
|
||||
// Get the last page read
|
||||
int DataFlash_Purple::GetPage()
|
||||
int16_t DataFlash_Purple::GetPage()
|
||||
{
|
||||
return(df_Read_PageAdr-1);
|
||||
}
|
||||
|
||||
void DataFlash_Purple::StartRead(int PageAdr)
|
||||
void DataFlash_Purple::StartRead(int16_t PageAdr)
|
||||
{
|
||||
df_Read_BufferNum=1;
|
||||
df_Read_BufferIdx=0;
|
||||
|
@ -433,22 +433,22 @@ byte DataFlash_Purple::ReadByte()
|
|||
return result;
|
||||
}
|
||||
|
||||
int DataFlash_Purple::ReadInt()
|
||||
int16_t DataFlash_Purple::ReadInt()
|
||||
{
|
||||
int result;
|
||||
uint16_t result;
|
||||
|
||||
result = ReadByte(); // High byte
|
||||
result = (result<<8) | ReadByte(); // Low byte
|
||||
return result;
|
||||
return (int16_t)result;
|
||||
}
|
||||
|
||||
long DataFlash_Purple::ReadLong()
|
||||
int32_t DataFlash_Purple::ReadLong()
|
||||
{
|
||||
long result;
|
||||
uint32_t result;
|
||||
|
||||
result = ReadByte(); // First byte
|
||||
result = (result<<8) | ReadByte();
|
||||
result = (result<<8) | ReadByte();
|
||||
result = (result<<8) | ReadByte(); // Last byte
|
||||
return result;
|
||||
return (int32_t)result;
|
||||
}
|
||||
|
|
|
@ -19,14 +19,14 @@ class DataFlash_Purple : public DataFlash_Class
|
|||
unsigned char df_Read_END;
|
||||
unsigned char df_Stop_Write;
|
||||
//Methods
|
||||
unsigned char BufferRead (unsigned char BufferNum, unsigned int IntPageAdr);
|
||||
void BufferWrite (unsigned char BufferNum, unsigned int IntPageAdr, unsigned char Data);
|
||||
void BufferToPage (unsigned char BufferNum, unsigned int PageAdr, unsigned char wait);
|
||||
void PageToBuffer(unsigned char BufferNum, unsigned int PageAdr);
|
||||
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();
|
||||
unsigned int PageSize();
|
||||
uint16_t PageSize();
|
||||
|
||||
unsigned char SPI_transfer(unsigned char data);
|
||||
void CS_inactive();
|
||||
|
@ -37,28 +37,28 @@ class DataFlash_Purple : public DataFlash_Class
|
|||
unsigned char df_manufacturer;
|
||||
unsigned char df_device_0;
|
||||
unsigned char df_device_1;
|
||||
unsigned int df_PageSize;
|
||||
uint16_t df_PageSize;
|
||||
|
||||
DataFlash_Purple(); // Constructor
|
||||
void Init();
|
||||
void ReadManufacturerID();
|
||||
int CardInserted();
|
||||
int GetPage();
|
||||
int GetWritePage();
|
||||
void PageErase (unsigned int PageAdr);
|
||||
bool CardInserted();
|
||||
int16_t GetPage();
|
||||
int16_t GetWritePage();
|
||||
void PageErase (uint16_t PageAdr);
|
||||
void ChipErase ();
|
||||
// Write methods
|
||||
void StartWrite(int PageAdr);
|
||||
void StartWrite(int16_t PageAdr);
|
||||
void FinishWrite();
|
||||
void WriteByte(unsigned char data);
|
||||
void WriteInt(int data);
|
||||
void WriteLong(long data);
|
||||
void WriteInt(int16_t data);
|
||||
void WriteLong(int32_t data);
|
||||
|
||||
// Read methods
|
||||
void StartRead(int PageAdr);
|
||||
void StartRead(int16_t PageAdr);
|
||||
unsigned char ReadByte();
|
||||
int ReadInt();
|
||||
long ReadLong();
|
||||
int16_t ReadInt();
|
||||
int32_t ReadLong();
|
||||
};
|
||||
|
||||
#endif
|
||||
|
|
Loading…
Reference in New Issue