|
|
@ -1494,10 +1494,12 @@ void AP_BLHeli::log_bidir_telemetry(void) |
|
|
|
trpm = trpm * 200 / motor_poles; |
|
|
|
trpm = trpm * 200 / motor_poles; |
|
|
|
} |
|
|
|
} |
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
if (trpm > 0) { |
|
|
|
last_log_ms[last_telem_esc] = now; |
|
|
|
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()); |
|
|
|
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 (!SRV_Channels::have_digital_outputs()) { |
|
|
|
if (!SRV_Channels::have_digital_outputs()) { |
|
|
|
return; |
|
|
|
return; |
|
|
|