Copter: only print perf data when SCHED_DEBUG is non-zero

This commit is contained in:
Andrew Tridgell 2013-01-12 12:06:40 +11:00
parent dcb181d2d8
commit 0fe7901422
1 changed files with 6 additions and 6 deletions

View File

@ -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;
}