mirror of https://github.com/ArduPilot/ardupilot
AP_Param: throw error if we lose parameters
if we can't save a parameter due to the queue size not being large enough then there is a coding error, likely the code trying to save large numbers of parameters while armed
This commit is contained in:
parent
d0d5dfddda
commit
faf769d8cd
|
@ -1266,6 +1266,7 @@ void AP_Param::save(bool force_save)
|
||||||
if (hal.util->get_soft_armed() && hal.scheduler->in_main_thread()) {
|
if (hal.util->get_soft_armed() && hal.scheduler->in_main_thread()) {
|
||||||
// if we are armed in main thread then don't sleep, instead we lose the
|
// if we are armed in main thread then don't sleep, instead we lose the
|
||||||
// parameter save
|
// parameter save
|
||||||
|
INTERNAL_ERROR(AP_InternalError::error_t::flow_of_control);
|
||||||
return;
|
return;
|
||||||
}
|
}
|
||||||
// when we are disarmed then loop waiting for a slot to become
|
// when we are disarmed then loop waiting for a slot to become
|
||||||
|
|
Loading…
Reference in New Issue