ArduPilot存储管理 Storage EEPROM Flash

AP_HAL::Storage
此类可以应用于所有平台。PX4v1平台支持8k的EEPROM,Pixhawk平台支持16k的FRAM铁电存储器

存储大小定义:libraries/AP_HAL/AP_HAL_Boards.h中HAL_STORAGE_SIZE

The DataFlash library
DataFlash是用来存储日志的。日志有固定的格式,固定的日志头和日志包头

//`日志头格式`
// structure used to define logging format
struct LogStructure {
    uint8_t msg_type;
    uint8_t msg_len;
    const char name[5];
    const char format[16];
    const char labels[64];
};

//`日志包头`
#define LOG_PACKET_HEADER          uint8_t head1, head2, msgid;

日志举例
libraries/DataFlash/examples/DataFlash_test/DataFlash_test.cpp

struct PACKED log_Test {
    LOG_PACKET_HEADER;
    uint16_t v1, v2, v3, v4;
    int32_t  l1, l2;
};

日志是以文件的形式存储到microSD card,可以直接拔出SD卡拷贝到PC

每个页首都有“日志文件的编号”和“日志文件的页号”。当用户下载日志时,非常有用

bool DataFlash_Block::WritePrioritisedBlock(const void *pBuffer, uint16_t size,
    bool is_critical)
{
    // is_critical is ignored - we're a ring buffer and never run out
    // of space.  possibly if we do more complicated bandwidth
    // limiting we can reservice bandwidth based on is_critical

    if (!CardInserted() || !log_write_started || !_writes_enabled) {

        return false;
    }

    if (! WriteBlockCheckStartupMessages()) {

        return false;
    }

    while (size > 0) {//while 判断条件 
        uint16_t n = df_PageSize - df_BufferIdx;
        if (n > size) {
            n = size;
        }

        if (df_BufferIdx == 0) {
            // if we are at the start of a page we need to insert a
            // page header
            if (n > df_PageSize - sizeof(struct PageHeader)) {
                n = df_PageSize - sizeof(struct PageHeader);
            }

            struct PageHeader ph = { df_FileNumber, df_FilePage };// df_FileNumber, df_FilePage 初始化中从SD卡中读回  add 0xff

            BlockWrite(df_BufferNum, df_BufferIdx, &ph, sizeof(ph), pBuffer, n);//df_BufferNum 缓存区编号 0/1
            df_BufferIdx += n + sizeof(ph);
        } else {

            BlockWrite(df_BufferNum, df_BufferIdx, NULL, 0, pBuffer, n);
            df_BufferIdx += n;
        }

        size -= n;
        pBuffer = (const void *)(n + (uintptr_t)pBuffer);

        if (df_BufferIdx == df_PageSize) {

            FinishWrite();
            df_FilePage++;
        }
    }

    return true;
}

日志按块读写
用户需要设置page大小512 byte,当写满一页以后告诉芯片复制一页

日志本身是通过DataFlash_File.cpp写到SD卡,还提供了DataFlash_Empty.cpp的块设备读写接口,下面是应用铁电的读写实例

//缓冲区buffer
static uint8_t buffer[2][DF_PAGE_SIZE]; 

void DataFlash_Flash::Init(const struct LogStructure *structure, uint8_t num_types)
{
    DataFlash_Backend::Init(structure, num_types);
    if (flash_fd == 0) {
        flash_fd = open(MTD_LOG_FILE, O_RDWR, 0777);
        if (flash_fd == -1) {
            printf("DataFlash_Flash init failed
");
        }
    }

    df_PageSize = DF_PAGE_SIZE; //页大小
    df_NumPages = DF_NUM_PAGES - 1; //页数量
}

//读取flash数据到buffer
void DataFlash_Flash::PageToBuffer(unsigned char BufferNum, uint16_t PageAdr)
{
    PageAdr -= 1;

    uint16_t ofs = PageAdr * DF_PAGE_SIZE;

    memset(buffer[BufferNum], 0, DF_PAGE_SIZE);

    if (lseek(flash_fd, ofs, SEEK_SET) != ofs) {
        printf("PageToBuffer lseek err.
");
        return;
    }
    if (read(flash_fd, buffer[BufferNum], DF_PAGE_SIZE) != DF_PAGE_SIZE)
    {
        printf("PageToBuffer read err.
");
        return;
    }
}

//记录需要写入flash的页地址和缓冲区编号
void DataFlash_Flash::BufferToPage (unsigned char BufferNum, uint16_t PageAdr, unsigned char wait)
{   
    PageAdr -= 1;
    uint16_t ofs = PageAdr * DF_PAGE_SIZE;

    if(flash_fd < 0) return;

    if (lseek(flash_fd, ofs, SEEK_SET) != ofs) {
        printf("BufferToPage lseek err.
");
        return;
    }

    if (::write(flash_fd, &buffer[BufferNum], DF_PAGE_SIZE) != DF_PAGE_SIZE)
    {
        printf("BufferToPage write err.
");
        return;
    }
}

//数据写入缓冲区
void DataFlash_Flash::BlockWrite(uint8_t BufferNum, uint16_t IntPageAdr,
                                const void *pHeader, uint8_t hdr_size,
                                const void *pBuffer, uint16_t size)
{
   if (!_writes_enabled) {
        return;
    }

    memset(&buffer[BufferNum][IntPageAdr], 0, size+hdr_size);

    if (hdr_size) {
        memcpy(&buffer[BufferNum][IntPageAdr],
               pHeader,
               hdr_size);
    }

    memcpy(&buffer[BufferNum][IntPageAdr+hdr_size],
           pBuffer,
           size);
}

//从缓冲区读取数据
bool DataFlash_Flash::BlockRead(uint8_t BufferNum, uint16_t IntPageAdr, void *pBuffer, uint16_t size)
{
    memset(pBuffer, 0, size);
    memcpy(pBuffer, &buffer[BufferNum][IntPageAdr], size);

    return true;
}
原文地址:https://www.cnblogs.com/zhangxuechao/p/11709531.html