Copter: free allocations in case of allocation failure
[ardupilot.git] / libraries / AP_Logger / AP_Logger_W25NXX.h
blobc384fa97db3e4c735e15cea1befc464eeadd84b3
1 /*
2 logging for block based dataflash devices on SPI
3 */
4 #pragma once
6 #include "AP_Logger_config.h"
8 #if HAL_LOGGING_FLASH_W25NXX_ENABLED
10 #include <AP_HAL/AP_HAL.h>
12 #include "AP_Logger_Block.h"
14 class AP_Logger_W25NXX : public AP_Logger_Block {
15 public:
16 AP_Logger_W25NXX(AP_Logger &front, LoggerMessageWriter_DFLogStart *writer) :
17 AP_Logger_Block(front, writer) {}
18 static AP_Logger_Backend *probe(AP_Logger &front,
19 LoggerMessageWriter_DFLogStart *ls) {
20 return NEW_NOTHROW AP_Logger_W25NXX(front, ls);
22 void Init(void) override;
23 bool CardInserted() const override { return !flash_died && df_NumPages > 0; }
25 private:
26 void BufferToPage(uint32_t PageAdr) override;
27 void PageToBuffer(uint32_t PageAdr) override;
28 void SectorErase(uint32_t SectorAdr) override;
29 void Sector4kErase(uint32_t SectorAdr) override;
30 void StartErase() override;
31 bool InErase() override;
32 void send_command_addr(uint8_t cmd, uint32_t address);
33 void WaitReady();
34 bool Busy();
35 uint8_t ReadStatusRegBits(uint8_t bits);
36 void WriteStatusReg(uint8_t reg, uint8_t bits);
38 void WriteEnable();
39 bool getSectorCount(void);
41 AP_HAL::OwnPtr<AP_HAL::SPIDevice> dev;
42 AP_HAL::Semaphore *dev_sem;
44 uint32_t flash_blockNum;
46 bool flash_died;
47 uint32_t erase_start_ms;
48 uint16_t erase_block;
49 bool read_cache_valid;
52 #endif // HAL_LOGGING_FLASH_W25NXX_ENABLED