mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
AP_FlashIFace: make sure device is locked before reset
only lock device in normal mode
This commit is contained in:
parent
a7ac4809b1
commit
f441ba21ee
@ -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;
|
||||||
|
Loading…
Reference in New Issue
Block a user