Real-time collaboration for Jupyter Notebooks, Linux Terminals, LaTeX, VS Code, R IDE, and more,
all in one place. Commercial Alternative to JupyterHub.
Real-time collaboration for Jupyter Notebooks, Linux Terminals, LaTeX, VS Code, R IDE, and more,
all in one place. Commercial Alternative to JupyterHub.
Path: blob/master/libraries/AP_FlashIface/AP_FlashIface_Abstract.h
Views: 1798
/*1* This file is free software: you can redistribute it and/or modify it2* under the terms of the GNU General Public License as published by the3* Free Software Foundation, either version 3 of the License, or4* (at your option) any later version.5*6* This file is distributed in the hope that it will be useful, but7* WITHOUT ANY WARRANTY; without even the implied warranty of8* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.9* See the GNU General Public License for more details.10*11* You should have received a copy of the GNU General Public License along12* with this program. If not, see <http://www.gnu.org/licenses/>.13*14* Code by15* Andy Piper16* Siddharth Bharat Purohit, Cubepilot Pty. Ltd.17*/18/*19Implements Common frontend methods for Flash Interface Driver20*/21#pragma once2223#include <AP_HAL/AP_HAL.h>2425class AP_FlashIface26{2728public:29virtual bool init() = 0;3031/**32* @details Read data from flash chip.33*34* @param[in] offset address offset from where to start the read35* @param[out] data data to be read from the device36* @param[in] size size of the data to be read37* @return The operation status.38* @retval false if the operation failed.39* @retval true if the operation succeeded.40*41*/42virtual bool read(uint32_t offset, uint8_t* data, uint32_t size) = 0;4344/**45* @details Gets number bytes that can be written in one go (page size).46*47* @return page size in bytes.48*49*/50virtual uint32_t get_page_size() const = 0;5152/**53* @details Gets number pages, each page can written in one go54*55* @return Number of pages.56*57*/58virtual uint32_t get_page_count() const = 0;5960/**61* @details Sends command to start programming a page of the chip.62*63* @param[in] page Page number to be written to64* @param[in] data data to be written65* @param[out] delay_us Time to wait until next is_device_busy call66* @param[out] timeout_us Time after which the erase should be timedout,67* should be reset at every call.68* @return The operation status.69* @retval false if the operation failed.70* @retval true if the operation succeeded.71*72*/73virtual bool start_program_page(uint32_t page, const uint8_t *data, uint32_t &delay_us, uint32_t &timeout_us) = 0;7475/**76* @details Tries to program as much as possible starting from the offset77* until size. User needs to call this as many times as needed78* taking already programmed bytes into account.79*80* @param[in] offset address offset for program81* @param[in] data data to be programmed82* @param[in] size size desired to be programmed83* @param[out] programming number of bytes programming, taking care of the limits84* @param[out] delay_us Time to wait until program typically finishes85* @param[out] timeout_us Time by which current program should have timedout.86* @return The operation status.87* @retval false if the operation failed.88* @retval true if the operation succeeded.89*90*/91virtual bool start_program_offset(uint32_t offset, const uint8_t* data, uint32_t size, uint32_t &programming,92uint32_t &delay_us, uint32_t &timeout_us)93{94return false;95}9697/**98* @details Gets number bytes that can erased in one go(sector size)99*100* @return Sector size in bytes.101*102*/103virtual uint32_t get_sector_size() const = 0;104105106/**107* @details Gets number of sectors, each sector can be erased in one go108*109* @return Number of sectors.110*111*/112virtual uint32_t get_sector_count() const = 0;113114/**115* @details Sends command to erase the entire chips.116*117* @param[out] delay_ms Time to wait until next is_device_busy call118* @param[out] timeout_ms Time by which the erase should have timedout119*120* @return The operation status.121* @retval false if the operation failed.122* @retval true if the operation succeeded.123*124*/125virtual bool start_mass_erase(uint32_t &delay_ms, uint32_t &timeout_ms) = 0;126127/**128* @details Sends command to erase a sector of the chip.129*130* @param[in] sector Sector number to be erased131* @param[out] delay_ms Time to wait until next is_device_busy call132* @param[out] timeout_ms Time by which the erase should have timedout133*134* @return The operation status.135* @retval false if the operation failed.136* @retval true if the operation succeeded.137*138*/139virtual bool start_sector_erase(uint32_t sector, uint32_t &delay_ms, uint32_t &timeout_ms) = 0;140141/**142* @details Tries to erase as much as possible starting from the offset143* until size. User needs to call this as many times as needed144* taking already erased bytes into account, until desired erase145* has taken place146*147* @param[in] offset address offset for erase148* @param[in] size size desired to be erased149* @param[out] erasing number of bytes erasing150* @param[out] delay_ms Time to wait until next is_device_busy call151* @param[out] timeout_ms Time by which the erase should have timedout152*153* @return The operation status.154* @retval false if the operation failed.155* @retval true if the operation succeeded.156*157*/158virtual bool start_erase_offset(uint32_t offset, uint32_t size, uint32_t &erasing,159uint32_t &delay_ms, uint32_t &timeout_ms)160{161return false;162}163164/**165* @details Check if the device is busy.166*167* @return device busy with last op.168*169* @retval false if the device is ready.170* @retval true if the device is busy.171*172*/173virtual bool is_device_busy() = 0;174175176/**177* @details Check if selected sector is erased.178*179* @param[in] sector sector for which to check erase180* @return The operation status.181* @retval false if the operation failed.182* @retval true if the operation succeeded.183*184*/185virtual bool verify_sector_erase(uint32_t sector) = 0;186187/**188* @details minimum number of bytes that can be erased189*190* @return Number of bytes.191*192*/193virtual uint32_t min_erase_size() const = 0;194195/**196* @details Starts execution in place mode197*198* @return if successfully entered XIP mode.199*200* @retval false the device failed to enter XIP mode.201* @retval true the device has entered XIP mode.202*203*/204virtual bool start_xip_mode(void** addr) { return false; }205206virtual bool stop_xip_mode() { return false; }207};208209210