Path: blob/master/libraries/AP_FlashIface/examples/jedec_test/jedec_test.cpp
9584 views
#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#endif3940static AP_SerialManager serial_manager;41static AP_BoardConfig board_config;4243static UNUSED_FUNCTION void test_page_program()44{45uint8_t *data = new uint8_t[jedec_dev.get_page_size()];46if (data == nullptr) {47hal.console->printf("Failed to allocate data for program");48}49uint8_t *rdata = new uint8_t[jedec_dev.get_page_size()];50if (rdata == nullptr) {51hal.console->printf("Failed to allocate data for read");52}5354// fill program data with its own address55for (uint32_t i = 0; i < jedec_dev.get_page_size(); i++) {56data[i] = i;57}58hal.console->printf("Writing Page #1\n");59uint32_t delay_us, timeout_us;60uint64_t start_time_us = AP_HAL::micros64();61if (!jedec_dev.start_program_page(0, data, delay_us, timeout_us)) {62hal.console->printf("Page write command failed\n");63return;64}65while (true) {66DELAY_MICROS(delay_us);67if (AP_HAL::micros64() > (start_time_us+delay_us)) {68if (!jedec_dev.is_device_busy()) {69hal.console->printf("Page Program Successful, elapsed %ld us\n", (unsigned long)(AP_HAL::micros64() - start_time_us));70break;71} else {72hal.console->printf("Typical page program time reached, Still Busy?!\n");73}74}75if (AP_HAL::micros64() > (start_time_us+timeout_us)) {76hal.console->printf("Page Program Timed out, elapsed %lld us\n", (unsigned long long)(AP_HAL::micros64() - start_time_us));77return;78}79}80if (!jedec_dev.read(0, rdata, jedec_dev.get_page_size())) {81hal.console->printf("Failed to read Flash page\n");82} else {83if (memcmp(data, rdata, jedec_dev.get_page_size()) != 0) {84hal.console->printf("Program Data Mismatch!\n");85} else {86hal.console->printf("Program Data Verified Good!\n");87}88}8990// Now test XIP mode here as well91uint8_t *chip_data = nullptr;92if (!jedec_dev.start_xip_mode((void**)&chip_data)) {93hal.console->printf("Failed to setup XIP mode\n");94}95if (chip_data == nullptr) {96hal.console->printf("Invalid address!\n");97}98// Here comes the future!99if (memcmp(data, chip_data, jedec_dev.get_page_size()) != 0) {100hal.console->printf("Program Data Mismatch in XIP mode!\n");101} else {102hal.console->printf("Program Data Verified Good in XIP mode!\n");103}104jedec_dev.stop_xip_mode();105}106107static UNUSED_FUNCTION void test_sector_erase()108{109uint32_t delay_ms, timeout_ms;110if (!jedec_dev.start_sector_erase(0, delay_ms, timeout_ms)) { // erase first sector111hal.console->printf("Sector erase command failed\n");112return;113}114uint32_t erase_start = AP_HAL::millis();115uint32_t next_check_ms = 0;116hal.console->printf("Erasing Sector #1 ");117while (true) {118if (AP_HAL::millis() > next_check_ms) {119hal.console->printf("\n");120if (!jedec_dev.is_device_busy()) {121if (next_check_ms == 0) {122hal.console->printf("Sector Erase happened too fast\n");123return;124}125hal.console->printf("Sector Erase Successful, elapsed %ld ms\n", (unsigned long)(AP_HAL::millis() - erase_start));126break;127} else {128hal.console->printf("Still busy erasing, elapsed %ld ms\n", (unsigned long)(AP_HAL::millis() - erase_start));129}130if ((AP_HAL::millis() - erase_start) > timeout_ms) {131hal.console->printf("Sector Erase Timed Out, elapsed %ld ms\n", (unsigned long)(AP_HAL::millis() - erase_start));132return;133}134next_check_ms = erase_start+delay_ms;135}136DELAY_MILLIS((delay_ms/100) + 10);137hal.console->printf("*");138}139if (!jedec_dev.verify_sector_erase(0)) {140hal.console->printf("Erase Verification Failed!\n");141} else {142hal.console->printf("Erase Verification Successful!\n");143}144}145146static UNUSED_FUNCTION void test_mass_erase()147{148uint32_t delay_ms, timeout_ms;149if (!jedec_dev.start_mass_erase(delay_ms, timeout_ms)) {150hal.console->printf("Mass erase command failed\n");151return;152}153uint32_t erase_start = AP_HAL::millis();154uint32_t next_check_ms = 0;155hal.console->printf("Mass Erasing ");156while (true) {157if (AP_HAL::millis() > next_check_ms) {158hal.console->printf("\n");159if (!jedec_dev.is_device_busy()) {160if (next_check_ms == 0) {161hal.console->printf("Sector Erase happened too fast\n");162return;163}164hal.console->printf("Mass Erase Successful, elapsed %ld ms\n",(unsigned long)(AP_HAL::millis() - erase_start));165return;166} else {167hal.console->printf("Still busy erasing, elapsed %ld ms\n", (unsigned long)(AP_HAL::millis() - erase_start));168}169if ((AP_HAL::millis() - erase_start) > timeout_ms) {170hal.console->printf("Mass Erase Timed Out, elapsed %ld ms\n", (unsigned long)(AP_HAL::millis() - erase_start));171return;172}173next_check_ms = erase_start+delay_ms;174}175DELAY_MILLIS(delay_ms/100);176hal.console->printf("*");177}178}179180void setup()181{182board_config.init();183serial_manager.init();184}185186void loop()187{188// Start on user input189hal.console->printf("\n\n******************Starting Test********************\n");190jedec_dev.init();191test_sector_erase();192test_page_program();193// test_mass_erase();194hal.scheduler->delay(1000);195}196197#endif198199AP_HAL_MAIN();200201202203