fixed PM logging rate.

git-svn-id: https://arducopter.googlecode.com/svn/trunk@1571 f9c3cf11-9bcb-44bc-f272-b75c42450872
This commit is contained in:
jasonshort 2011-01-29 04:58:31 +00:00
parent b3334b71bd
commit 70f11ef88d

View File

@ -464,16 +464,14 @@ void loop()
medium_loopTimer = millis();
medium_loop();
/* commented out temporarily
if (millis() - perf_mon_timer > 20000) {
if (mainLoop_count != 0) {
GCS.send_message(MSG_PERF_REPORT);
if (log_bitmask & MASK_LOG_PM)
send_message(MSG_PERF_REPORT);
if (log_bitmask & MASK_LOG_PM){
Log_Write_Performance();
resetPerfData();
}
}*/
resetPerfData();
perf_mon_timer = millis();
}
}
}
@ -639,15 +637,6 @@ void medium_loop()
do_something_usefull();
#endif
if (millis() - perf_mon_timer > 20000) {
if (mainLoop_count != 0) {
send_message(MSG_PERF_REPORT);
if (log_bitmask & MASK_LOG_PM)
Log_Write_Performance();
resetPerfData();
}
}
}