mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-25 09:13:57 -04:00
fixed PM logging rate.
git-svn-id: https://arducopter.googlecode.com/svn/trunk@1571 f9c3cf11-9bcb-44bc-f272-b75c42450872
This commit is contained in:
parent
43620dd50b
commit
1af6a3b4e8
@ -464,16 +464,14 @@ void loop()
|
|||||||
medium_loopTimer = millis();
|
medium_loopTimer = millis();
|
||||||
medium_loop();
|
medium_loop();
|
||||||
|
|
||||||
/* commented out temporarily
|
|
||||||
if (millis() - perf_mon_timer > 20000) {
|
if (millis() - perf_mon_timer > 20000) {
|
||||||
if (mainLoop_count != 0) {
|
send_message(MSG_PERF_REPORT);
|
||||||
GCS.send_message(MSG_PERF_REPORT);
|
if (log_bitmask & MASK_LOG_PM){
|
||||||
if (log_bitmask & MASK_LOG_PM)
|
|
||||||
Log_Write_Performance();
|
Log_Write_Performance();
|
||||||
|
|
||||||
resetPerfData();
|
|
||||||
}
|
}
|
||||||
}*/
|
resetPerfData();
|
||||||
|
perf_mon_timer = millis();
|
||||||
|
}
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
@ -639,15 +637,6 @@ void medium_loop()
|
|||||||
do_something_usefull();
|
do_something_usefull();
|
||||||
#endif
|
#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();
|
|
||||||
}
|
|
||||||
}
|
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
||||||
|
Loading…
Reference in New Issue
Block a user