AP_FlashIFace: make sure device is locked before reset

only lock device in normal mode
This commit is contained in:
Andy Piper 2021-09-05 17:25:05 +01:00 committed by Peter Hall
parent a7ac4809b1
commit f441ba21ee

View File

@ -162,6 +162,10 @@ void AP_FlashIface_JEDEC::reset_device()
{ {
// Get chip out of XIP mode // Get chip out of XIP mode
AP_HAL::QSPIDevice::CommandHeader cmd; AP_HAL::QSPIDevice::CommandHeader cmd;
#ifndef HAL_BOOTLOADER_BUILD // this is required in order to run jedec_test with a regular bootloader
_dev->get_semaphore()->take_blocking();
#endif
/* Single line CMD_RESET_MEMORY command.*/ /* Single line CMD_RESET_MEMORY command.*/
cmd.cmd = CMD_RESET_ENABLE; cmd.cmd = CMD_RESET_ENABLE;
cmd.cfg = AP_HAL::QSPI::CFG_CMD_MODE_ONE_LINE; cmd.cfg = AP_HAL::QSPI::CFG_CMD_MODE_ONE_LINE;