Copter: avoid division by zero in compass/motor interference calibration

This commit is contained in:
Peter Barker 2021-10-16 09:37:03 +11:00 committed by Randy Mackay
parent dc5a25edbd
commit 9f17cd62a2
1 changed files with 3 additions and 3 deletions

View File

@ -160,6 +160,9 @@ MAV_RESULT Copter::mavlink_compassmot(const GCS_MAVLINK &gcs_chan)
throttle_pct = (float)channel_throttle->get_control_in() / 1000.0f;
throttle_pct = constrain_float(throttle_pct,0.0f,1.0f);
// record maximum throttle
throttle_pct_max = MAX(throttle_pct_max, throttle_pct);
if (!battery.current_amps(current)) {
current = 0;
}
@ -211,9 +214,6 @@ MAV_RESULT Copter::mavlink_compassmot(const GCS_MAVLINK &gcs_chan)
interference_pct[i] = motor_compensation[i].length() * (current_amps_max/throttle_pct_max) / (float)arming.compass_magfield_expected() * 100.0f;
}
}
// record maximum throttle
throttle_pct_max = MAX(throttle_pct_max, throttle_pct);
}
if (AP_HAL::millis() - last_send_time > 500) {