APM:Libraries
DataFlash_Revo.h
Go to the documentation of this file.
1 /* ************************************************************ */
2 /* DataFlash_Revo Log library */
3 /* ************************************************************ */
4 #pragma once
5 
6 #if CONFIG_HAL_BOARD == HAL_BOARD_F4LIGHT
7 
8 #include <AP_HAL/AP_HAL.h>
9 #include "DataFlash_Backend.h"
11 #include <AP_HAL_F4Light/GPIO.h>
12 
13 
14 // flash size
15 #define DF_PAGE_SIZE 256L
16 
17 #define DF_RESET BOARD_DATAFLASH_CS_PIN // RESET (PB3)
18 
19 //Micron M25P16 Serial Flash Embedded Memory 16 Mb, 3V
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
28 
29 #define JEDEC_BULK_ERASE 0xC7
30 #define JEDEC_SECTOR_ERASE 0x20 // 4k erase
31 #define JEDEC_PAGE_ERASE 0xD8 // 64K erase
32 
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
41 
42 
43 using namespace F4Light;
44 
45 
47 {
48 private:
49  //Methods
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);
53  void WaitReady();
54  uint8_t ReadStatusReg();
55  uint16_t PageSize() { return df_PageSize; }
56  void PageErase (uint16_t PageAdr);
57  void BlockErase (uint16_t BlockAdr);
58  void ChipErase();
59 
60  void Flash_Jedec_WriteEnable();
61  void Flash_Jedec_EraseSector(uint32_t chip_offset);
62 
63  // write size bytes of data to a page. The caller must ensure that
64  // the data fits within the page, otherwise it will wrap to the
65  // start of the page
66  // If pHeader is not nullptr then write the header bytes before the data
67  void BlockWrite(uint8_t BufferNum, uint16_t IntPageAdr,
68  const void *pHeader, uint8_t hdr_size,
69  const void *pBuffer, uint16_t size);
70 
71  // read size bytes of data to a page. The caller must ensure that
72  // the data fits within the page, otherwise it will wrap to the
73  // start of the page
74  bool BlockRead(uint8_t BufferNum, uint16_t IntPageAdr, void *pBuffer, uint16_t size);
75 
76 
80  static bool log_write_started;
81 
82  static bool _sem_take(uint8_t timeout); // take a semaphore safely
83 
84  bool cs_assert(); // Select device
85  void cs_release(); // Deselect device
86 
87 // uint8_t spi_read(void) { uint8_t b; _spi->transfer(NULL,0, &b, 1); return b; }
88  inline void spi_write(uint8_t b) { _spi->transfer(&b,1, NULL, 0); }
89  inline void spi_write(int data) { spi_write((uint8_t)data); }
90 
91  static bool flash_died;
92 
93 //[ from died Dataflash_Block
94 
95  struct PageHeader {
96  uint16_t FileNumber;
97  uint16_t FilePage;
98  };
99 
100  // DataFlash Log variables...
101  uint8_t df_BufferNum;
103  uint16_t df_BufferIdx;
105  uint16_t df_PageAdr;
106  uint16_t df_Read_PageAdr;
107  uint16_t df_FileNumber;
108  uint16_t df_FilePage;
109 
110  // offset from adding FMT messages to log data
112 
113  // erase handling
114  bool NeedErase(void);
115 
116  // internal high level functions
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);
126 
127  // Read methods
128  bool ReadBlock(void *pBuffer, uint16_t size);
129 
130  // file numbers
131  void SetFileNumber(uint16_t FileNumber);
132  uint16_t GetFilePage();
133  uint16_t GetFileNumber();
134 
135  uint8_t erase_cmd;
136  uint32_t erase_size;
137  uint16_t last_block_num;
138 
139 protected:
141  uint16_t df_device;
142 
143  // page handling
144  uint16_t df_PageSize;
145  uint32_t df_NumPages;
146 
147  bool WritesOK() const override;
148 
149 //]
150 
151 
152 public:
154  DataFlash_Backend(front, writer) { }
155 
156  void Init() override;
157  void ReadManufacturerID();
158  bool CardInserted(void) const { return true; }
159 
160  uint8_t ReadStatus();
161 
162  bool logging_enabled() const { return true; }
163  bool logging_failed() const { return false; };
164 
165  void stop_logging(void) { log_write_started = false; }
166 
167 //[ from died Dataflash_Block
168 
169  // erase handling
170  void EraseAll();
171 
172  bool NeedPrep(void);
173  void Prep();
174 
175  /* Write a block of data at current offset */
176  bool _WritePrioritisedBlock(const void *pBuffer, uint16_t size, bool is_critical);
177 
178  // high level interface
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;
183 
184  void get_log_info(uint16_t log_num, uint32_t &size, uint32_t &time_utc);
185 
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);
188 
189  uint32_t bufferspace_available();
190 
191  bool logging_started(void) const { return log_write_started; }
192 };
193 
194 #endif // CONFIG_HAL_BOARD == HAL_BOARD_Revo
uint16_t df_FilePage
uint8_t df_manufacturer
uint16_t PageSize()
uint16_t df_Read_PageAdr
void stop_logging(void)
static AP_HAL::OwnPtr< AP_HAL::SPIDevice > _spi
static AP_HAL::Semaphore * _spi_sem
uint32_t df_NumPages
DataFlash_Revo(DataFlash_Class &front, DFMessageWriter_DFLogStart *writer)
uint16_t last_block_num
static bool flash_died
-*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
bool logging_started(void) const
uint32_t erase_size
uint16_t df_BufferIdx
void spi_write(int data)
uint8_t df_BufferNum
bool logging_enabled() const
bool CardInserted(void) const
void spi_write(uint8_t b)
bool logging_failed() const
uint16_t df_device
#define NULL
Definition: hal_types.h:59
uint16_t df_PageAdr
virtual bool transfer(const uint8_t *send, uint32_t send_len, uint8_t *recv, uint32_t recv_len) override=0
static uint16_t log_num
uint8_t df_Read_BufferNum
uint16_t df_Read_BufferIdx
uint16_t df_PageSize
uint16_t df_FileNumber
static bool log_write_started