6 #if CONFIG_HAL_BOARD == HAL_BOARD_F4LIGHT 15 #define DF_PAGE_SIZE 256L 17 #define DF_RESET BOARD_DATAFLASH_CS_PIN // RESET (PB3) 20 #define JEDEC_WRITE_ENABLE 0x06 21 #define JEDEC_WRITE_DISABLE 0x04 22 #define JEDEC_READ_STATUS 0x05 23 #define JEDEC_WRITE_STATUS 0x01 24 #define JEDEC_READ_DATA 0x03 25 #define JEDEC_FAST_READ 0x0b 26 #define JEDEC_DEVICE_ID 0x9F 27 #define JEDEC_PAGE_WRITE 0x02 29 #define JEDEC_BULK_ERASE 0xC7 30 #define JEDEC_SECTOR_ERASE 0x20 // 4k erase 31 #define JEDEC_PAGE_ERASE 0xD8 // 64K erase 33 #define JEDEC_STATUS_BUSY 0x01 34 #define JEDEC_STATUS_WRITEPROTECT 0x02 35 #define JEDEC_STATUS_BP0 0x04 36 #define JEDEC_STATUS_BP1 0x08 37 #define JEDEC_STATUS_BP2 0x10 38 #define JEDEC_STATUS_TP 0x20 39 #define JEDEC_STATUS_SEC 0x40 40 #define JEDEC_STATUS_SRP0 0x80 50 void BufferWrite (uint8_t BufferNum, uint16_t IntPageAdr, uint8_t Data);
51 void BufferToPage (uint8_t BufferNum, uint16_t PageAdr, uint8_t wait);
52 void PageToBuffer(uint8_t BufferNum, uint16_t PageAdr);
54 uint8_t ReadStatusReg();
56 void PageErase (uint16_t PageAdr);
57 void BlockErase (uint16_t BlockAdr);
60 void Flash_Jedec_WriteEnable();
61 void Flash_Jedec_EraseSector(uint32_t chip_offset);
67 void BlockWrite(uint8_t BufferNum, uint16_t IntPageAdr,
68 const void *pHeader, uint8_t hdr_size,
69 const void *pBuffer, uint16_t size);
74 bool BlockRead(uint8_t BufferNum, uint16_t IntPageAdr,
void *pBuffer, uint16_t size);
82 static bool _sem_take(uint8_t timeout);
114 bool NeedErase(
void);
117 void StartRead(uint16_t PageAdr);
118 uint16_t find_last_page(
void);
119 uint16_t find_last_page_of_log(uint16_t log_number);
120 bool check_wrapped(
void);
121 uint16_t GetPage(
void);
122 uint16_t GetWritePage(
void);
123 void StartWrite(uint16_t PageAdr);
124 void FinishWrite(
void);
125 bool getSectorCount(uint32_t *ptr);
128 bool ReadBlock(
void *pBuffer, uint16_t size);
131 void SetFileNumber(uint16_t FileNumber);
132 uint16_t GetFilePage();
133 uint16_t GetFileNumber();
147 bool WritesOK()
const override;
156 void Init()
override;
157 void ReadManufacturerID();
160 uint8_t ReadStatus();
176 bool _WritePrioritisedBlock(
const void *pBuffer, uint16_t size,
bool is_critical);
179 uint16_t get_num_logs()
override;
180 uint16_t start_new_log(
void);
181 void get_log_boundaries(uint16_t
log_num, uint16_t & start_page, uint16_t & end_page);
182 uint16_t find_last_log()
override;
184 void get_log_info(uint16_t log_num, uint32_t &size, uint32_t &time_utc);
186 int16_t get_log_data_raw(uint16_t log_num, uint16_t page, uint32_t offset, uint16_t len, uint8_t *data);
187 int16_t get_log_data(uint16_t log_num, uint16_t page, uint32_t offset, uint16_t len, uint8_t *data);
189 uint32_t bufferspace_available();
194 #endif // CONFIG_HAL_BOARD == HAL_BOARD_Revo
static AP_HAL::OwnPtr< AP_HAL::SPIDevice > _spi
static AP_HAL::Semaphore * _spi_sem
DataFlash_Revo(DataFlash_Class &front, DFMessageWriter_DFLogStart *writer)
-*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
bool logging_started(void) const
bool logging_enabled() const
bool CardInserted(void) const
void spi_write(uint8_t b)
bool logging_failed() const
virtual bool transfer(const uint8_t *send, uint32_t send_len, uint8_t *recv, uint32_t recv_len) override=0
uint8_t df_Read_BufferNum
uint16_t df_Read_BufferIdx
static bool log_write_started