DataFlash: added F4Light HAL support
This commit is contained in:
parent
2b213b78ab
commit
0d8c71de71
@ -3,8 +3,13 @@
|
|||||||
#include "DataFlash_Backend.h"
|
#include "DataFlash_Backend.h"
|
||||||
|
|
||||||
#include "DataFlash_File.h"
|
#include "DataFlash_File.h"
|
||||||
|
#include "DataFlash_File_sd.h"
|
||||||
#include "DataFlash_MAVLink.h"
|
#include "DataFlash_MAVLink.h"
|
||||||
#include <GCS_MAVLink/GCS.h>
|
#include <GCS_MAVLink/GCS.h>
|
||||||
|
#if CONFIG_HAL_BOARD == HAL_BOARD_F4LIGHT
|
||||||
|
#include "DataFlash_Revo.h"
|
||||||
|
#endif
|
||||||
|
|
||||||
|
|
||||||
DataFlash_Class *DataFlash_Class::_instance;
|
DataFlash_Class *DataFlash_Class::_instance;
|
||||||
|
|
||||||
@ -76,7 +81,7 @@ void DataFlash_Class::Init(const struct LogStructure *structures, uint8_t num_ty
|
|||||||
_num_types = num_types;
|
_num_types = num_types;
|
||||||
_structures = structures;
|
_structures = structures;
|
||||||
|
|
||||||
#if (HAL_OS_POSIX_IO || HAL_OS_FATFS_IO) && defined(HAL_BOARD_LOG_DIRECTORY)
|
#if defined(HAL_BOARD_LOG_DIRECTORY)
|
||||||
if (_params.backend_types == DATAFLASH_BACKEND_FILE ||
|
if (_params.backend_types == DATAFLASH_BACKEND_FILE ||
|
||||||
_params.backend_types == DATAFLASH_BACKEND_BOTH) {
|
_params.backend_types == DATAFLASH_BACKEND_BOTH) {
|
||||||
DFMessageWriter_DFLogStart *message_writer =
|
DFMessageWriter_DFLogStart *message_writer =
|
||||||
@ -92,6 +97,24 @@ void DataFlash_Class::Init(const struct LogStructure *structures, uint8_t num_ty
|
|||||||
_next_backend++;
|
_next_backend++;
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
#elif CONFIG_HAL_BOARD == HAL_BOARD_F4LIGHT // restore dataflash logs
|
||||||
|
|
||||||
|
if (_params.backend_types == DATAFLASH_BACKEND_FILE ||
|
||||||
|
_params.backend_types == DATAFLASH_BACKEND_BOTH) {
|
||||||
|
|
||||||
|
DFMessageWriter_DFLogStart *message_writer =
|
||||||
|
new DFMessageWriter_DFLogStart(_firmware_string);
|
||||||
|
if (message_writer != nullptr) {
|
||||||
|
|
||||||
|
backends[_next_backend] = new DataFlash_Revo(*this, message_writer);
|
||||||
|
}
|
||||||
|
|
||||||
|
if (backends[_next_backend] == nullptr) {
|
||||||
|
hal.console->printf("Unable to open DataFlash_Revo");
|
||||||
|
} else {
|
||||||
|
_next_backend++;
|
||||||
|
}
|
||||||
|
}
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#if DATAFLASH_MAVLINK_SUPPORT
|
#if DATAFLASH_MAVLINK_SUPPORT
|
||||||
|
1191
libraries/DataFlash/DataFlash_File_sd.cpp
Normal file
1191
libraries/DataFlash/DataFlash_File_sd.cpp
Normal file
File diff suppressed because it is too large
Load Diff
155
libraries/DataFlash/DataFlash_File_sd.h
Normal file
155
libraries/DataFlash/DataFlash_File_sd.h
Normal file
@ -0,0 +1,155 @@
|
|||||||
|
/*
|
||||||
|
DataFlash logging - file oriented variant
|
||||||
|
|
||||||
|
This uses posix file IO to create log files called logNN.dat in the
|
||||||
|
given directory
|
||||||
|
*/
|
||||||
|
#pragma once
|
||||||
|
|
||||||
|
#include <AP_HAL/AP_HAL.h>
|
||||||
|
|
||||||
|
#if CONFIG_HAL_BOARD == HAL_BOARD_F4LIGHT && (defined(BOARD_SDCARD_NAME) || defined(BOARD_DATAFLASH_FATFS))
|
||||||
|
|
||||||
|
#include <AP_HAL/utility/RingBuffer.h>
|
||||||
|
#include "DataFlash_Backend.h"
|
||||||
|
|
||||||
|
#include <sd/SD.h>
|
||||||
|
|
||||||
|
class DataFlash_File : public DataFlash_Backend
|
||||||
|
{
|
||||||
|
public:
|
||||||
|
// constructor
|
||||||
|
DataFlash_File(DataFlash_Class &front,
|
||||||
|
DFMessageWriter_DFLogStart *,
|
||||||
|
const char *log_directory);
|
||||||
|
|
||||||
|
// initialisation
|
||||||
|
void Init() override;
|
||||||
|
bool CardInserted(void) const;
|
||||||
|
|
||||||
|
// erase handling
|
||||||
|
void EraseAll();
|
||||||
|
|
||||||
|
// possibly time-consuming preparation handling:
|
||||||
|
bool NeedPrep();
|
||||||
|
void Prep();
|
||||||
|
|
||||||
|
/* Write a block of data at current offset */
|
||||||
|
bool _WritePrioritisedBlock(const void *pBuffer, uint16_t size, bool is_critical);
|
||||||
|
uint32_t bufferspace_available();
|
||||||
|
|
||||||
|
// high level interface
|
||||||
|
uint16_t find_last_log() override;
|
||||||
|
void get_log_boundaries(uint16_t log_num, uint16_t & start_page, uint16_t & end_page);
|
||||||
|
void get_log_info(uint16_t log_num, uint32_t &size, uint32_t &time_utc);
|
||||||
|
int16_t get_log_data(uint16_t log_num, uint16_t page, uint32_t offset, uint16_t len, uint8_t *data);
|
||||||
|
uint16_t get_num_logs() override;
|
||||||
|
uint16_t start_new_log(void) override;
|
||||||
|
void LogReadProcess(const uint16_t log_num,
|
||||||
|
uint16_t start_page, uint16_t end_page,
|
||||||
|
print_mode_fn print_mode,
|
||||||
|
AP_HAL::BetterStream *port);
|
||||||
|
void DumpPageInfo(AP_HAL::BetterStream *port);
|
||||||
|
void ShowDeviceInfo(AP_HAL::BetterStream *port);
|
||||||
|
void ListAvailableLogs(AP_HAL::BetterStream *port);
|
||||||
|
|
||||||
|
void periodic_1Hz(const uint32_t now) override;
|
||||||
|
void periodic_fullrate(const uint32_t now);
|
||||||
|
|
||||||
|
// this method is used when reporting system status over mavlink
|
||||||
|
bool logging_enabled() const;
|
||||||
|
bool logging_failed() const;
|
||||||
|
|
||||||
|
void vehicle_was_disarmed() override;
|
||||||
|
|
||||||
|
bool logging_started(void) const override { return !(!(_write_fd)); }
|
||||||
|
|
||||||
|
void PrepForArming();
|
||||||
|
|
||||||
|
protected:
|
||||||
|
bool WritesOK() const override;
|
||||||
|
bool StartNewLogOK() const override;
|
||||||
|
|
||||||
|
private:
|
||||||
|
File _write_fd;
|
||||||
|
File _read_fd;
|
||||||
|
uint16_t _read_fd_log_num;
|
||||||
|
uint32_t _read_offset;
|
||||||
|
uint32_t _write_offset;
|
||||||
|
volatile bool _open_error;
|
||||||
|
const char *_log_directory;
|
||||||
|
|
||||||
|
uint32_t _io_timer_heartbeat;
|
||||||
|
bool io_thread_alive() const;
|
||||||
|
|
||||||
|
uint16_t _cached_oldest_log;
|
||||||
|
uint16_t _last_oldest_log;
|
||||||
|
|
||||||
|
/*
|
||||||
|
read a block
|
||||||
|
*/
|
||||||
|
bool ReadBlock(void *pkt, uint16_t size) override;
|
||||||
|
|
||||||
|
uint16_t _log_num_from_list_entry(const uint16_t list_entry);
|
||||||
|
|
||||||
|
// possibly time-consuming preparations handling
|
||||||
|
void Prep_MinSpace();
|
||||||
|
uint16_t find_oldest_log();
|
||||||
|
|
||||||
|
bool file_exists(const char *filename) const;
|
||||||
|
bool log_exists(const uint16_t lognum) const;
|
||||||
|
|
||||||
|
const float min_avail_space_percent = 10.0f;
|
||||||
|
|
||||||
|
// write buffer
|
||||||
|
ByteBuffer _writebuf;
|
||||||
|
const uint16_t _writebuf_chunk;
|
||||||
|
uint32_t _last_write_time;
|
||||||
|
|
||||||
|
/* construct a file name given a log number. Caller must free. */
|
||||||
|
char *_log_file_name(const uint16_t log_num) const;
|
||||||
|
char *_lastlog_file_name() const;
|
||||||
|
uint32_t _get_log_size(const uint16_t log_num) const;
|
||||||
|
uint32_t _get_log_time(const uint16_t log_num) const;
|
||||||
|
|
||||||
|
void stop_logging(void);
|
||||||
|
|
||||||
|
void _io_timer(void);
|
||||||
|
|
||||||
|
uint32_t critical_message_reserved_space() const {
|
||||||
|
// possibly make this a proportional to buffer size?
|
||||||
|
uint32_t ret = 1024;
|
||||||
|
if (ret > _writebuf.get_size()) {
|
||||||
|
// in this case you will only get critical messages
|
||||||
|
ret = _writebuf.get_size();
|
||||||
|
}
|
||||||
|
return ret;
|
||||||
|
};
|
||||||
|
uint32_t non_messagewriter_message_reserved_space() const {
|
||||||
|
// possibly make this a proportional to buffer size?
|
||||||
|
uint32_t ret = 1024;
|
||||||
|
if (ret >= _writebuf.get_size()) {
|
||||||
|
// need to allow messages out from the messagewriters. In
|
||||||
|
// this case while you have a messagewriter you won't get
|
||||||
|
// any other messages. This should be a corner case!
|
||||||
|
ret = 0;
|
||||||
|
}
|
||||||
|
return ret;
|
||||||
|
};
|
||||||
|
|
||||||
|
float avail_space_percent(uint32_t *free = NULL);
|
||||||
|
|
||||||
|
AP_HAL::Semaphore *semaphore;
|
||||||
|
|
||||||
|
bool has_data;
|
||||||
|
|
||||||
|
#define Daysto32(year, mon) (((year - 1) / 4) + MONTAB(year)[mon])
|
||||||
|
|
||||||
|
/////////////////////////////////////////////////////////////////////
|
||||||
|
|
||||||
|
static uint32_t to_timestamp(const struct tm *t);
|
||||||
|
|
||||||
|
bool _busy;
|
||||||
|
};
|
||||||
|
|
||||||
|
#endif
|
1092
libraries/DataFlash/DataFlash_Revo.cpp
Normal file
1092
libraries/DataFlash/DataFlash_Revo.cpp
Normal file
File diff suppressed because it is too large
Load Diff
201
libraries/DataFlash/DataFlash_Revo.h
Normal file
201
libraries/DataFlash/DataFlash_Revo.h
Normal file
@ -0,0 +1,201 @@
|
|||||||
|
/* ************************************************************ */
|
||||||
|
/* DataFlash_Revo Log library */
|
||||||
|
/* ************************************************************ */
|
||||||
|
#pragma once
|
||||||
|
|
||||||
|
#if CONFIG_HAL_BOARD == HAL_BOARD_F4LIGHT
|
||||||
|
|
||||||
|
#include <AP_HAL/AP_HAL.h>
|
||||||
|
#include "DataFlash_Backend.h"
|
||||||
|
#include <AP_HAL_F4Light/AP_HAL_F4Light.h>
|
||||||
|
#include <AP_HAL_F4Light/GPIO.h>
|
||||||
|
|
||||||
|
|
||||||
|
// flash size
|
||||||
|
#define DF_PAGE_SIZE 256L
|
||||||
|
|
||||||
|
#define DF_RESET BOARD_DATAFLASH_CS_PIN // RESET (PB3)
|
||||||
|
|
||||||
|
//Micron M25P16 Serial Flash Embedded Memory 16 Mb, 3V
|
||||||
|
#define JEDEC_WRITE_ENABLE 0x06
|
||||||
|
#define JEDEC_WRITE_DISABLE 0x04
|
||||||
|
#define JEDEC_READ_STATUS 0x05
|
||||||
|
#define JEDEC_WRITE_STATUS 0x01
|
||||||
|
#define JEDEC_READ_DATA 0x03
|
||||||
|
#define JEDEC_FAST_READ 0x0b
|
||||||
|
#define JEDEC_DEVICE_ID 0x9F
|
||||||
|
#define JEDEC_PAGE_WRITE 0x02
|
||||||
|
|
||||||
|
#define JEDEC_BULK_ERASE 0xC7
|
||||||
|
#define JEDEC_SECTOR_ERASE 0x20 // 4k erase
|
||||||
|
#define JEDEC_PAGE_ERASE 0xD8 // 64K erase
|
||||||
|
|
||||||
|
#define JEDEC_STATUS_BUSY 0x01
|
||||||
|
#define JEDEC_STATUS_WRITEPROTECT 0x02
|
||||||
|
#define JEDEC_STATUS_BP0 0x04
|
||||||
|
#define JEDEC_STATUS_BP1 0x08
|
||||||
|
#define JEDEC_STATUS_BP2 0x10
|
||||||
|
#define JEDEC_STATUS_TP 0x20
|
||||||
|
#define JEDEC_STATUS_SEC 0x40
|
||||||
|
#define JEDEC_STATUS_SRP0 0x80
|
||||||
|
|
||||||
|
|
||||||
|
using namespace F4Light;
|
||||||
|
|
||||||
|
|
||||||
|
class DataFlash_Revo : public DataFlash_Backend
|
||||||
|
{
|
||||||
|
private:
|
||||||
|
//Methods
|
||||||
|
void BufferWrite (uint8_t BufferNum, uint16_t IntPageAdr, uint8_t Data);
|
||||||
|
void BufferToPage (uint8_t BufferNum, uint16_t PageAdr, uint8_t wait);
|
||||||
|
void PageToBuffer(uint8_t BufferNum, uint16_t PageAdr);
|
||||||
|
void WaitReady();
|
||||||
|
uint8_t ReadStatusReg();
|
||||||
|
uint16_t PageSize() { return df_PageSize; }
|
||||||
|
void PageErase (uint16_t PageAdr);
|
||||||
|
void BlockErase (uint16_t BlockAdr);
|
||||||
|
void ChipErase();
|
||||||
|
|
||||||
|
void Flash_Jedec_WriteEnable();
|
||||||
|
void Flash_Jedec_EraseSector(uint32_t chip_offset);
|
||||||
|
|
||||||
|
// 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 nullptr 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);
|
||||||
|
|
||||||
|
|
||||||
|
//////////////////
|
||||||
|
static AP_HAL::OwnPtr<AP_HAL::SPIDevice> _spi;
|
||||||
|
static AP_HAL::Semaphore *_spi_sem;
|
||||||
|
static bool log_write_started;
|
||||||
|
|
||||||
|
static bool _sem_take(uint8_t timeout); // take a semaphore safely
|
||||||
|
|
||||||
|
bool cs_assert(); // Select device
|
||||||
|
void cs_release(); // Deselect device
|
||||||
|
|
||||||
|
// uint8_t spi_read(void) { uint8_t b; _spi->transfer(NULL,0, &b, 1); return b; }
|
||||||
|
inline void spi_write(uint8_t b) { _spi->transfer(&b,1, NULL, 0); }
|
||||||
|
inline void spi_write(int data) { spi_write((uint8_t)data); }
|
||||||
|
|
||||||
|
static bool flash_died;
|
||||||
|
|
||||||
|
//[ from died Dataflash_Block
|
||||||
|
|
||||||
|
struct PageHeader {
|
||||||
|
uint16_t FileNumber;
|
||||||
|
uint16_t FilePage;
|
||||||
|
};
|
||||||
|
|
||||||
|
// DataFlash Log variables...
|
||||||
|
uint8_t df_BufferNum;
|
||||||
|
uint8_t df_Read_BufferNum;
|
||||||
|
uint16_t df_BufferIdx;
|
||||||
|
uint16_t df_Read_BufferIdx;
|
||||||
|
uint16_t df_PageAdr;
|
||||||
|
uint16_t df_Read_PageAdr;
|
||||||
|
uint16_t df_FileNumber;
|
||||||
|
uint16_t df_FilePage;
|
||||||
|
|
||||||
|
// offset from adding FMT messages to log data
|
||||||
|
bool adding_fmt_headers;
|
||||||
|
|
||||||
|
// erase handling
|
||||||
|
bool NeedErase(void);
|
||||||
|
|
||||||
|
// internal high level functions
|
||||||
|
void StartRead(uint16_t PageAdr);
|
||||||
|
uint16_t find_last_page(void);
|
||||||
|
uint16_t find_last_page_of_log(uint16_t log_number);
|
||||||
|
bool check_wrapped(void);
|
||||||
|
uint16_t GetPage(void);
|
||||||
|
uint16_t GetWritePage(void);
|
||||||
|
void StartWrite(uint16_t PageAdr);
|
||||||
|
void FinishWrite(void);
|
||||||
|
bool getSectorCount(uint32_t *ptr);
|
||||||
|
|
||||||
|
// Read methods
|
||||||
|
bool ReadBlock(void *pBuffer, uint16_t size);
|
||||||
|
|
||||||
|
// file numbers
|
||||||
|
void SetFileNumber(uint16_t FileNumber);
|
||||||
|
uint16_t GetFilePage();
|
||||||
|
uint16_t GetFileNumber();
|
||||||
|
|
||||||
|
uint8_t erase_cmd;
|
||||||
|
uint32_t erase_size;
|
||||||
|
uint16_t last_block_num;
|
||||||
|
|
||||||
|
protected:
|
||||||
|
uint8_t df_manufacturer;
|
||||||
|
uint16_t df_device;
|
||||||
|
|
||||||
|
// page handling
|
||||||
|
uint16_t df_PageSize;
|
||||||
|
uint32_t df_NumPages;
|
||||||
|
|
||||||
|
bool WritesOK() const override;
|
||||||
|
|
||||||
|
//]
|
||||||
|
|
||||||
|
|
||||||
|
public:
|
||||||
|
DataFlash_Revo(DataFlash_Class &front, DFMessageWriter_DFLogStart *writer) :
|
||||||
|
DataFlash_Backend(front, writer) { }
|
||||||
|
|
||||||
|
void Init() override;
|
||||||
|
void ReadManufacturerID();
|
||||||
|
bool CardInserted(void) const { return true; }
|
||||||
|
|
||||||
|
uint8_t ReadStatus();
|
||||||
|
|
||||||
|
bool logging_enabled() const { return true; }
|
||||||
|
bool logging_failed() const { return false; };
|
||||||
|
|
||||||
|
void stop_logging(void) { log_write_started = false; }
|
||||||
|
|
||||||
|
//[ from died Dataflash_Block
|
||||||
|
|
||||||
|
// erase handling
|
||||||
|
void EraseAll();
|
||||||
|
|
||||||
|
bool NeedPrep(void);
|
||||||
|
void Prep();
|
||||||
|
|
||||||
|
/* Write a block of data at current offset */
|
||||||
|
bool _WritePrioritisedBlock(const void *pBuffer, uint16_t size, bool is_critical);
|
||||||
|
|
||||||
|
// high level interface
|
||||||
|
uint16_t get_num_logs() override;
|
||||||
|
uint16_t start_new_log(void);
|
||||||
|
void get_log_boundaries(uint16_t log_num, uint16_t & start_page, uint16_t & end_page);
|
||||||
|
uint16_t find_last_log() override;
|
||||||
|
void LogReadProcess(const uint16_t list_entry,
|
||||||
|
uint16_t start_page, uint16_t end_page,
|
||||||
|
print_mode_fn print_mode,
|
||||||
|
AP_HAL::BetterStream *port);
|
||||||
|
void get_log_info(uint16_t log_num, uint32_t &size, uint32_t &time_utc);
|
||||||
|
void DumpPageInfo(AP_HAL::BetterStream *port);
|
||||||
|
void ShowDeviceInfo(AP_HAL::BetterStream *port);
|
||||||
|
void ListAvailableLogs(AP_HAL::BetterStream *port);
|
||||||
|
|
||||||
|
|
||||||
|
int16_t get_log_data_raw(uint16_t log_num, uint16_t page, uint32_t offset, uint16_t len, uint8_t *data);
|
||||||
|
int16_t get_log_data(uint16_t log_num, uint16_t page, uint32_t offset, uint16_t len, uint8_t *data);
|
||||||
|
|
||||||
|
uint32_t bufferspace_available();
|
||||||
|
|
||||||
|
bool logging_started(void) const { return log_write_started; }
|
||||||
|
};
|
||||||
|
|
||||||
|
#endif // CONFIG_HAL_BOARD == HAL_BOARD_Revo
|
@ -14,7 +14,10 @@
|
|||||||
|
|
||||||
#include "DataFlash.h"
|
#include "DataFlash.h"
|
||||||
#include "DataFlash_File.h"
|
#include "DataFlash_File.h"
|
||||||
|
#include "DataFlash_File_sd.h"
|
||||||
#include "DataFlash_MAVLink.h"
|
#include "DataFlash_MAVLink.h"
|
||||||
|
#include "DataFlash_Revo.h"
|
||||||
|
#include "DataFlash_File_sd.h"
|
||||||
#include "DFMessageWriter.h"
|
#include "DFMessageWriter.h"
|
||||||
|
|
||||||
extern const AP_HAL::HAL& hal;
|
extern const AP_HAL::HAL& hal;
|
||||||
|
Loading…
Reference in New Issue
Block a user