From 0fe790142210ae916f4d49ee5bdd45422e9bfd7a Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Sat, 12 Jan 2013 12:06:40 +1100 Subject: [PATCH] Copter: only print perf data when SCHED_DEBUG is non-zero --- ArduCopter/ArduCopter.pde | 12 ++++++------ 1 file changed, 6 insertions(+), 6 deletions(-) diff --git a/ArduCopter/ArduCopter.pde b/ArduCopter/ArduCopter.pde index 602727938a..0f9e275be0 100644 --- a/ArduCopter/ArduCopter.pde +++ b/ArduCopter/ArduCopter.pde @@ -991,12 +991,12 @@ static void perf_update(void) { if (g.log_bitmask & MASK_LOG_PM) Log_Write_Performance(); -#if 1 - cliSerial->printf_P(PSTR("PERF: %u/%u %lu\n"), - (unsigned)perf_info_get_num_long_running(), - (unsigned)perf_info_get_num_loops(), - (unsigned long)perf_info_get_max_time()); -#endif + if (scheduler.debug()) { + cliSerial->printf_P(PSTR("PERF: %u/%u %lu\n"), + (unsigned)perf_info_get_num_long_running(), + (unsigned)perf_info_get_num_loops(), + (unsigned long)perf_info_get_max_time()); + } perf_info_reset(); gps_fix_count = 0; }