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_JEDEC.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 Flash Interface Driver based on20Open Standard Published by JEDEC21*/2223#include "AP_FlashIface_Abstract.h"242526class AP_FlashIface_JEDEC : public AP_FlashIface27{28public:29bool init() override;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*/42bool read(uint32_t offset, uint8_t *data, uint32_t size) override;434445/**46* @details Gets number bytes that can be written in one go (page size).47*48* @return page size in bytes.49*50*/51uint32_t get_page_size() const override52{53return _desc.page_size;54}5556/**57* @details Gets number pages, each page can written in one go58*59* @return Number of pages.60*61*/62uint32_t get_page_count() const override63{64return _desc.page_count;65}6667/**68* @details Sends command to start programming a page of the chip.69*70* @param[in] page Page number to be written to71* @param[in] data data to be written72* @param[out] delay_us Time to wait until next is_device_busy call73* @param[out] timeout_us Time after which the erase should be timedout,74* should be reset at every call.75* @return The operation status.76* @retval false if the operation failed.77* @retval true if the operation succeeded.78*79*/80bool start_program_page(uint32_t page, const uint8_t *data, uint32_t &delay_us, uint32_t &timeout_us) override;8182/**83* @details Tries to program as much as possible starting from the offset84* until size. User needs to call this as many times as needed85* taking already programmed bytes into account.86*87* @param[in] offset address offset for program88* @param[in] data data to be programmed89* @param[in] size size desired to be programmed90* @param[out] programming number of bytes programming, taking care of the limits91* @param[out] delay_us Time to wait until program typically finishes92* @param[out] timeout_us Time by which current program should have timedout.93* @return The operation status.94* @retval false if the operation failed.95* @retval true if the operation succeeded.96*97*/98bool start_program_offset(uint32_t offset, const uint8_t* data, uint32_t size, uint32_t &programming,99uint32_t &delay_us, uint32_t &timeout_us) override;100101// Erase Methods102103/**104* @details Sends command to erase the entire chip.105*106* @param[out] delay_ms Time to wait until next is_device_busy call107* @param[out] timeout_ms Time by which the erase should have timedout108*109* @return The operation status.110* @retval false if the operation failed.111* @retval true if the operation succeeded.112*113*/114bool start_mass_erase(uint32_t &delay_ms, uint32_t &timeout_ms) override;115116/**117* @details Gets number bytes that can erased in one go(sector size)118*119* @return Sector size in bytes.120*121*/122uint32_t get_sector_size() const override123{124return _desc.sector_size;125}126127/**128* @details Gets number of sectors, each sector can be erased in one go129*130* @return Number of sectors.131*132*/133uint32_t get_sector_count() const override134{135return _desc.sector_count;136}137138/**139* @details minimum number of bytes that can be erased140*141* @return Number of bytes.142*143*/144uint32_t min_erase_size() const override145{146return _desc.min_erase_size;147}148149150/**151* @details Sends command to erase a sector of the chip.152*153* @param[in] sector Sector number to be erased154* @param[out] delay_ms Time to wait until next is_device_busy call155* @param[out] timeout_ms Time by which the erase should have timedout156*157* @return The operation status.158* @retval false if the operation failed.159* @retval true if the operation succeeded.160*161*/162bool start_sector_erase(uint32_t sector, uint32_t &delay_ms, uint32_t &timeout_ms) override;163164/**165* @details Tries to erase as much as possible starting from the offset166* until size. User needs to call this as many times as needed167* taking already erased bytes into account, until desired erase168* has taken place169*170* @param[in] offset address offset for erase171* @param[in] size size desired to be erased172* @param[out] erasing number of bytes erasing173* @param[out] delay_ms Time to wait until next is_device_busy call174* @param[out] timeout_ms Time by which the erase should have timedout175*176* @return The operation status.177* @retval false if the operation failed.178* @retval true if the operation succeeded.179*180*/181bool start_erase_offset(uint32_t offset, uint32_t size, uint32_t &erasing,182uint32_t &delay_ms, uint32_t &timeout_ms) override;183184185/**186* @details Check if selected sector is erased.187*188* @param[in] sector sector for which to check erase189* @return The operation status.190* @retval false if the operation failed.191* @retval true if the operation succeeded.192*193*/194bool verify_sector_erase(uint32_t sector) override;195196197/**198* @details Check if the device is busy.199*200* @return device busy with last op.201*202* @retval false if the device is ready.203* @retval true if the device is busy.204*205*/206bool is_device_busy() override;207208209/**210* @details Starts execution in place mode211*212* @return if successfully entered XIP mode.213*214* @retval false the device failed to enter XIP mode.215* @retval true the device has entered XIP mode.216*217*/218bool start_xip_mode(void** addr) override;219220bool stop_xip_mode() override;221protected:222void reset_device();223224// Does initial configuration to bring up and setup chip225bool detect_device();226227// Configures device to normal working state, currently 4-4-4 WSPI228bool configure_device();229230// Enables commands that modify flash data or settings231bool write_enable();232233// Disables commands that modify flash data or settings234bool write_disable();235236// wait for the chip to be ready for the next instruction237void wait_ready();238239// Read modify write register240bool modify_reg(uint8_t read_ins, uint8_t write_ins,241uint8_t mask, uint8_t va_list);242243// reads a register value of chip using instruction244bool read_reg(uint8_t read_ins, uint8_t &read_val);245246// sends instruction to write a register value in the chip247bool write_reg(uint8_t read_ins, uint8_t write_val);248249// Sends WSPI command without data250bool send_cmd(uint8_t ins);251252// Is device in wide spi mode253enum class WSPIMode {254NormalSPI,255QuadSPI,256OctoSPI257} _wide_spi_mode;258259AP_HAL::OwnPtr<AP_HAL::WSPIDevice> _dev;260261enum xip_entry_methods {262XIP_ENTRY_METHOD_1,263XIP_ENTRY_METHOD_2,264XIP_ENTRY_METHOD_3265};266267// Device description extracted from SFDP268struct device_desc {269uint16_t param_rev; //parameter revision270uint8_t param_table_len; // size of parameter table271uint32_t param_table_pointer; // location of parameter table272uint32_t flash_size; // size of flash in bytes273uint32_t page_size; // maximum size that can be written in one transaction274uint32_t page_count; // number of pages each of page size275uint32_t sector_size; // maximum number of bytes that can be erased outside of mass erase276uint32_t sector_count; // number of sectors277uint32_t min_erase_size; // minimum amount of bytes that can be erased278struct {279uint8_t ins; // instruction for the erase280uint32_t size; // number of bytes that will be erased281uint32_t delay_ms; // typical time this command will finish282uint32_t timeout_ms; // time after which the erase cmd caller should time283} erase_type[4];284uint32_t mass_erase_delay_ms; // typical time taken while mass erase285uint32_t mass_erase_timeout_ms; // time after which mass erase cmd caller should timeout286uint8_t write_enable_ins; // instruction to allow enabling modification of register and data287uint32_t page_prog_delay_us; // time taken to write a page worth of data to flash288uint32_t page_prog_timeout_us; // time after which the page program caller should timeout289uint8_t fast_read_ins; // instruction to do fast read, i.e. read any number of bytes in single trx290uint8_t fast_read_dummy_cycles; // number of dummy cycles after which the chip will respond with data291uint8_t quad_mode_ins; // instruction to enter 4-4-4 mode292uint8_t wide_mode_enable;293bool quad_mode_rmw_seq; // use Read modify write sequence to enter 4-4-4 mode supported or not294uint8_t status_read_ins; // read status of the chip, gets us if busy writing/erasing295bool legacy_status_polling; // check if legacy status polling supported or not296bool is_xip_supported; // is execution in place or 0-4-4 mode supported297uint8_t fast_read_mode_clocks;298xip_entry_methods entry_method;299} _desc;300301uint8_t _dev_list_idx;302bool initialised;303bool write_enable_called;304};305306307308