Copter: perf info ignores slow loop due to arming

This commit is contained in:
Randy Mackay 2015-02-09 23:07:18 +09:00
parent 82df53ed80
commit 4ff75f0371
2 changed files with 17 additions and 0 deletions

View File

@ -199,6 +199,9 @@ static bool init_arm_motors(bool arming_from_gcs)
// reenable failsafe // reenable failsafe
failsafe_enable(); failsafe_enable();
// perf monitor ignores delay due to arming
perf_ignore_this_loop();
// flag exiting this function // flag exiting this function
in_arm_motors = false; in_arm_motors = false;

View File

@ -14,6 +14,7 @@
uint16_t perf_info_loop_count; uint16_t perf_info_loop_count;
uint32_t perf_info_max_time; uint32_t perf_info_max_time;
uint16_t perf_info_long_running; uint16_t perf_info_long_running;
bool perf_ignore_loop = false;
// perf_info_reset - reset all records of loop time to zero // perf_info_reset - reset all records of loop time to zero
void perf_info_reset() void perf_info_reset()
@ -23,10 +24,23 @@ void perf_info_reset()
perf_info_long_running = 0; perf_info_long_running = 0;
} }
// perf_ignore_loop - ignore this loop from performance measurements (used to reduce false positive when arming)
void perf_ignore_this_loop()
{
perf_ignore_loop = true;
}
// perf_info_check_loop_time - check latest loop time vs min, max and overtime threshold // perf_info_check_loop_time - check latest loop time vs min, max and overtime threshold
void perf_info_check_loop_time(uint32_t time_in_micros) void perf_info_check_loop_time(uint32_t time_in_micros)
{ {
perf_info_loop_count++; perf_info_loop_count++;
// exit if this loop should be ignored
if (perf_ignore_loop) {
perf_ignore_loop = false;
return;
}
if( time_in_micros > perf_info_max_time) { if( time_in_micros > perf_info_max_time) {
perf_info_max_time = time_in_micros; perf_info_max_time = time_in_micros;
} }