AP_Scheduler: params always use set method

This commit is contained in:
Iampete1 2022-07-05 04:08:56 +01:00 committed by Peter Hall
parent 63e58e4fa1
commit a0fc8cc46a

View File

@ -450,7 +450,7 @@ void AP_Scheduler::task_info(ExpandingString &str)
// dynamically enable statistics collection
if (!(_options & uint8_t(Options::RECORD_TASK_INFO))) {
_options |= uint8_t(Options::RECORD_TASK_INFO);
_options.set(_options | uint8_t(Options::RECORD_TASK_INFO));
return;
}