mirror of https://github.com/ArduPilot/ardupilot
AP_BLHeli: minor style fix for get_average_moto_frequency_hz
This commit is contained in:
parent
79e551b8d3
commit
bc1697fec3
|
@ -1305,7 +1305,7 @@ bool AP_BLHeli::get_telem_data(uint8_t esc_index, struct telem_data &td)
|
|||
float AP_BLHeli::get_average_motor_frequency_hz() const
|
||||
{
|
||||
float motor_freq = 0.0f;
|
||||
uint32_t now = AP_HAL::millis();
|
||||
const uint32_t now = AP_HAL::millis();
|
||||
uint8_t valid_escs = 0;
|
||||
// average the rpm of each motor as reported by BLHeli and convert to Hz
|
||||
for (uint8_t i = 0; i < num_motors; i++) {
|
||||
|
@ -1314,7 +1314,7 @@ float AP_BLHeli::get_average_motor_frequency_hz() const
|
|||
motor_freq += last_telem[i].rpm / 60.0f;
|
||||
}
|
||||
}
|
||||
if (valid_escs) {
|
||||
if (valid_escs > 0) {
|
||||
motor_freq /= valid_escs;
|
||||
}
|
||||
|
||||
|
|
Loading…
Reference in New Issue