Browse Source

AP_BLHeli: make ESC debug easier to see

apm_2208
Andy Piper 3 years ago committed by Andrew Tridgell
parent
commit
9753f36dd1
  1. 6
      libraries/AP_BLHeli/AP_BLHeli.cpp

6
libraries/AP_BLHeli/AP_BLHeli.cpp

@ -1494,8 +1494,10 @@ void AP_BLHeli::log_bidir_telemetry(void) @@ -1494,8 +1494,10 @@ void AP_BLHeli::log_bidir_telemetry(void)
trpm = trpm * 200 / motor_poles;
}
last_log_ms[last_telem_esc] = now;
DEV_PRINTF("ESC[%u] RPM=%u e=%.1f t=%u\n", last_telem_esc, trpm, hal.rcout->get_erpm_error_rate(motor_idx), (unsigned)AP_HAL::millis());
if (trpm > 0) {
last_log_ms[last_telem_esc] = now;
DEV_PRINTF("ESC[%u] RPM=%u e=%.1f t=%u\n", last_telem_esc, trpm, hal.rcout->get_erpm_error_rate(motor_idx), (unsigned)AP_HAL::millis());
}
}
}

Loading…
Cancel
Save