AP_Scheduler: add load_average() to PM log message

This commit is contained in:
Mark Whitehorn 2018-02-15 08:58:08 -07:00 committed by Randy Mackay
parent 90d32abd47
commit 919383a739
1 changed files with 2 additions and 1 deletions

View File

@ -273,7 +273,8 @@ void AP_Scheduler::Log_Write_Performance()
num_loops : perf_info.get_num_loops(),
max_time : perf_info.get_max_time(),
ins_error_count : AP::ins().error_count(),
mem_avail : hal.util->available_memory()
mem_avail : hal.util->available_memory(),
load : (uint16_t)(load_average() * 1000)
};
DataFlash_Class::instance()->WriteCriticalBlock(&pkt, sizeof(pkt));
}