mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-08 17:08:28 -04:00
DataFlash: update SITL implementaion for new API
This commit is contained in:
parent
3039c37f95
commit
8015f0f626
@ -97,11 +97,35 @@ void DataFlash_SITL::BufferWrite (unsigned char BufferNum, uint16_t IntPageAdr,
|
||||
buffer[BufferNum][IntPageAdr] = (uint8_t)Data;
|
||||
}
|
||||
|
||||
void DataFlash_SITL::BlockWrite(uint8_t BufferNum, uint16_t IntPageAdr,
|
||||
const void *pHeader, uint8_t hdr_size,
|
||||
const void *pBuffer, uint16_t size)
|
||||
{
|
||||
if (hdr_size) {
|
||||
memcpy(&buffer[BufferNum][IntPageAdr],
|
||||
pHeader,
|
||||
hdr_size);
|
||||
}
|
||||
memcpy(&buffer[BufferNum][IntPageAdr+hdr_size],
|
||||
pBuffer,
|
||||
size);
|
||||
}
|
||||
|
||||
unsigned char DataFlash_SITL::BufferRead (unsigned char BufferNum, uint16_t IntPageAdr)
|
||||
{
|
||||
return (unsigned char)buffer[BufferNum][IntPageAdr];
|
||||
}
|
||||
|
||||
// read size bytes of data to a page. The caller must ensure that
|
||||
// the data fits within the page, otherwise it will wrap to the
|
||||
// start of the page
|
||||
bool DataFlash_SITL::BlockRead(uint8_t BufferNum, uint16_t IntPageAdr, void *pBuffer, uint16_t size)
|
||||
{
|
||||
memcpy(pBuffer, &buffer[BufferNum][IntPageAdr], size);
|
||||
return true;
|
||||
}
|
||||
|
||||
|
||||
// *** END OF INTERNAL FUNCTIONS ***
|
||||
|
||||
void DataFlash_SITL::PageErase (uint16_t PageAdr)
|
||||
|
@ -24,6 +24,19 @@ private:
|
||||
void PageErase (uint16_t PageAdr);
|
||||
void BlockErase (uint16_t BlockAdr);
|
||||
void ChipErase();
|
||||
|
||||
// write size bytes of data to a page. The caller must ensure that
|
||||
// the data fits within the page, otherwise it will wrap to the
|
||||
// start of the page
|
||||
// If pHeader is not NULL then write the header bytes before the data
|
||||
void BlockWrite(uint8_t BufferNum, uint16_t IntPageAdr,
|
||||
const void *pHeader, uint8_t hdr_size,
|
||||
const void *pBuffer, uint16_t size);
|
||||
|
||||
// read size bytes of data to a page. The caller must ensure that
|
||||
// the data fits within the page, otherwise it will wrap to the
|
||||
// start of the page
|
||||
bool BlockRead(uint8_t BufferNum, uint16_t IntPageAdr, void *pBuffer, uint16_t size);
|
||||
|
||||
AP_HAL::SPIDeviceDriver *_spi;
|
||||
AP_HAL::Semaphore *_spi_sem;
|
||||
|
Loading…
Reference in New Issue
Block a user