Skip to content

Commit

Permalink
AP_Param: throw error if we lose parameters
Browse files Browse the repository at this point in the history
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
  • Loading branch information
tridge committed Aug 19, 2024
1 parent d0d5dfd commit faf769d
Showing 1 changed file with 1 addition and 0 deletions.
1 change: 1 addition & 0 deletions libraries/AP_Param/AP_Param.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -1266,6 +1266,7 @@ void AP_Param::save(bool force_save)
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
// parameter save
INTERNAL_ERROR(AP_InternalError::error_t::flow_of_control);
return;
}
// when we are disarmed then loop waiting for a slot to become
Expand Down

0 comments on commit faf769d

Please sign in to comment.