5
0
mirror of https://github.com/ArduPilot/ardupilot synced 2025-01-14 12:48:31 -04:00

Copter: a useful bit of timing debug code

enable when looking at main loop timing
This commit is contained in:
Andrew Tridgell 2013-01-07 11:04:27 +11:00
parent 647b3b09b6
commit d11dde578f

View File

@ -946,6 +946,16 @@ void loop()
// ----------------------------
if (main_loop_ready()) {
#if 0
uint16_t num_samples = ins.num_samples_available();
static uint16_t counter;
if (num_samples != 2 || (counter++ % 200 == 0)) {
cliSerial->printf_P(PSTR("num_samples=%u dt=%u\n"),
(unsigned)num_samples,
(unsigned)(timer - fast_loopTimer));
}
#endif
#if DEBUG_FAST_LOOP == ENABLED
Log_Write_Data(DATA_FAST_LOOP, (int32_t)(timer - fast_loopTimer));
#endif