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/examples/jedec_test/jedec_test.cpp
Views: 1800
#include <AP_HAL/AP_HAL.h>12#if CONFIG_HAL_BOARD == HAL_BOARD_LINUX34const AP_HAL::HAL& hal = AP_HAL::get_HAL();5void setup() { }67void loop()8{9// the library simply panics if a JEDEC device can't be found. We10// can't really recover from that.11hal.console->printf("No JEDEC on linux\n");12hal.scheduler->delay(1000);13}1415#else1617#include <GCS_MAVLink/GCS_Dummy.h>18#include <AP_SerialManager/AP_SerialManager.h>19#include <AP_BoardConfig/AP_BoardConfig.h>20#include <AP_FlashIface/AP_FlashIface.h>21#include <stdio.h>2223AP_FlashIface_JEDEC jedec_dev;24const AP_HAL::HAL& hal = AP_HAL::get_HAL();2526void setup();27void loop();2829GCS_Dummy _gcs;303132#ifdef HAL_BOOTLOADER_BUILD33#define DELAY_MILLIS(x) do { chThdSleepMilliseconds(x); } while(0)34#define DELAY_MICROS(x) do { chThdSleepMicroseconds(x); } while(0)35#else36#define DELAY_MILLIS(x) do { hal.scheduler->delay(x); } while(0)37#define DELAY_MICROS(x) do { hal.scheduler->delay_microseconds(x); } while(0)38#endif3940const AP_Param::GroupInfo GCS_MAVLINK_Parameters::var_info[] = {41AP_GROUPEND42};4344static AP_SerialManager serial_manager;45static AP_BoardConfig board_config;4647static UNUSED_FUNCTION void test_page_program()48{49uint8_t *data = new uint8_t[jedec_dev.get_page_size()];50if (data == nullptr) {51hal.console->printf("Failed to allocate data for program");52}53uint8_t *rdata = new uint8_t[jedec_dev.get_page_size()];54if (rdata == nullptr) {55hal.console->printf("Failed to allocate data for read");56}5758// fill program data with its own address59for (uint32_t i = 0; i < jedec_dev.get_page_size(); i++) {60data[i] = i;61}62hal.console->printf("Writing Page #1\n");63uint32_t delay_us, timeout_us;64uint64_t start_time_us = AP_HAL::micros64();65if (!jedec_dev.start_program_page(0, data, delay_us, timeout_us)) {66hal.console->printf("Page write command failed\n");67return;68}69while (true) {70DELAY_MICROS(delay_us);71if (AP_HAL::micros64() > (start_time_us+delay_us)) {72if (!jedec_dev.is_device_busy()) {73hal.console->printf("Page Program Successful, elapsed %ld us\n", (unsigned long)(AP_HAL::micros64() - start_time_us));74break;75} else {76hal.console->printf("Typical page program time reached, Still Busy?!\n");77}78}79if (AP_HAL::micros64() > (start_time_us+timeout_us)) {80hal.console->printf("Page Program Timed out, elapsed %lld us\n", (unsigned long long)(AP_HAL::micros64() - start_time_us));81return;82}83}84if (!jedec_dev.read(0, rdata, jedec_dev.get_page_size())) {85hal.console->printf("Failed to read Flash page\n");86} else {87if (memcmp(data, rdata, jedec_dev.get_page_size()) != 0) {88hal.console->printf("Program Data Mismatch!\n");89} else {90hal.console->printf("Program Data Verified Good!\n");91}92}9394// Now test XIP mode here as well95uint8_t *chip_data = nullptr;96if (!jedec_dev.start_xip_mode((void**)&chip_data)) {97hal.console->printf("Failed to setup XIP mode\n");98}99if (chip_data == nullptr) {100hal.console->printf("Invalid address!\n");101}102// Here comes the future!103if (memcmp(data, chip_data, jedec_dev.get_page_size()) != 0) {104hal.console->printf("Program Data Mismatch in XIP mode!\n");105} else {106hal.console->printf("Program Data Verified Good in XIP mode!\n");107}108jedec_dev.stop_xip_mode();109}110111static UNUSED_FUNCTION void test_sector_erase()112{113uint32_t delay_ms, timeout_ms;114if (!jedec_dev.start_sector_erase(0, delay_ms, timeout_ms)) { // erase first sector115hal.console->printf("Sector erase command failed\n");116return;117}118uint32_t erase_start = AP_HAL::millis();119uint32_t next_check_ms = 0;120hal.console->printf("Erasing Sector #1 ");121while (true) {122if (AP_HAL::millis() > next_check_ms) {123hal.console->printf("\n");124if (!jedec_dev.is_device_busy()) {125if (next_check_ms == 0) {126hal.console->printf("Sector Erase happened too fast\n");127return;128}129hal.console->printf("Sector Erase Successful, elapsed %ld ms\n", (unsigned long)(AP_HAL::millis() - erase_start));130break;131} else {132hal.console->printf("Still busy erasing, elapsed %ld ms\n", (unsigned long)(AP_HAL::millis() - erase_start));133}134if ((AP_HAL::millis() - erase_start) > timeout_ms) {135hal.console->printf("Sector Erase Timed Out, elapsed %ld ms\n", (unsigned long)(AP_HAL::millis() - erase_start));136return;137}138next_check_ms = erase_start+delay_ms;139}140DELAY_MILLIS((delay_ms/100) + 10);141hal.console->printf("*");142}143if (!jedec_dev.verify_sector_erase(0)) {144hal.console->printf("Erase Verification Failed!\n");145} else {146hal.console->printf("Erase Verification Successful!\n");147}148}149150static UNUSED_FUNCTION void test_mass_erase()151{152uint32_t delay_ms, timeout_ms;153if (!jedec_dev.start_mass_erase(delay_ms, timeout_ms)) {154hal.console->printf("Mass erase command failed\n");155return;156}157uint32_t erase_start = AP_HAL::millis();158uint32_t next_check_ms = 0;159hal.console->printf("Mass Erasing ");160while (true) {161if (AP_HAL::millis() > next_check_ms) {162hal.console->printf("\n");163if (!jedec_dev.is_device_busy()) {164if (next_check_ms == 0) {165hal.console->printf("Sector Erase happened too fast\n");166return;167}168hal.console->printf("Mass Erase Successful, elapsed %ld ms\n",(unsigned long)(AP_HAL::millis() - erase_start));169return;170} else {171hal.console->printf("Still busy erasing, elapsed %ld ms\n", (unsigned long)(AP_HAL::millis() - erase_start));172}173if ((AP_HAL::millis() - erase_start) > timeout_ms) {174hal.console->printf("Mass Erase Timed Out, elapsed %ld ms\n", (unsigned long)(AP_HAL::millis() - erase_start));175return;176}177next_check_ms = erase_start+delay_ms;178}179DELAY_MILLIS(delay_ms/100);180hal.console->printf("*");181}182}183184void setup()185{186board_config.init();187serial_manager.init();188}189190void loop()191{192// Start on user input193hal.console->printf("\n\n******************Starting Test********************\n");194jedec_dev.init();195test_sector_erase();196test_page_program();197// test_mass_erase();198hal.scheduler->delay(1000);199}200201#endif202203AP_HAL_MAIN();204205206207