mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-08 17:08:28 -04:00
DataFlash: fixed SITL dataflash logging
block numbers are 1 based
This commit is contained in:
parent
ed9f369492
commit
0a2f2619de
@ -13,6 +13,7 @@
|
||||
#include <sys/stat.h>
|
||||
#include <fcntl.h>
|
||||
#include <stdint.h>
|
||||
#include <assert.h>
|
||||
#include "DataFlash.h"
|
||||
|
||||
#define DF_PAGE_SIZE 512
|
||||
@ -85,12 +86,14 @@ void DataFlash_SITL::WaitReady()
|
||||
|
||||
void DataFlash_SITL::PageToBuffer(unsigned char BufferNum, uint16_t PageAdr)
|
||||
{
|
||||
pread(flash_fd, buffer[BufferNum], DF_PAGE_SIZE, PageAdr*DF_PAGE_SIZE);
|
||||
assert(PageAdr>=1);
|
||||
pread(flash_fd, buffer[BufferNum], DF_PAGE_SIZE, (PageAdr-1)*DF_PAGE_SIZE);
|
||||
}
|
||||
|
||||
void DataFlash_SITL::BufferToPage (unsigned char BufferNum, uint16_t PageAdr, unsigned char wait)
|
||||
{
|
||||
pwrite(flash_fd, buffer[BufferNum], DF_PAGE_SIZE, PageAdr*DF_PAGE_SIZE);
|
||||
assert(PageAdr>=1);
|
||||
pwrite(flash_fd, buffer[BufferNum], DF_PAGE_SIZE, (PageAdr-1)*(uint32_t)DF_PAGE_SIZE);
|
||||
}
|
||||
|
||||
void DataFlash_SITL::BufferWrite (unsigned char BufferNum, uint16_t IntPageAdr, unsigned char Data)
|
||||
@ -133,14 +136,16 @@ void DataFlash_SITL::PageErase (uint16_t PageAdr)
|
||||
{
|
||||
uint8_t fill[DF_PAGE_SIZE];
|
||||
memset(fill, 0xFF, sizeof(fill));
|
||||
pwrite(flash_fd, fill, DF_PAGE_SIZE, PageAdr*DF_PAGE_SIZE);
|
||||
assert(PageAdr>=1);
|
||||
pwrite(flash_fd, fill, DF_PAGE_SIZE, (PageAdr-1)*DF_PAGE_SIZE);
|
||||
}
|
||||
|
||||
void DataFlash_SITL::BlockErase (uint16_t BlockAdr)
|
||||
{
|
||||
uint8_t fill[DF_PAGE_SIZE*8];
|
||||
memset(fill, 0xFF, sizeof(fill));
|
||||
pwrite(flash_fd, fill, DF_PAGE_SIZE*8, BlockAdr*DF_PAGE_SIZE*8);
|
||||
assert(BlockAdr>=1);
|
||||
pwrite(flash_fd, fill, DF_PAGE_SIZE*8, (BlockAdr-1)*DF_PAGE_SIZE*8);
|
||||
}
|
||||
|
||||
|
||||
|
Loading…
Reference in New Issue
Block a user