mirror of https://github.com/ArduPilot/ardupilot
Copter: ensure esc calibration only occurs on next reboot
It was possible for a board with no safety switch attached to get stuck waiting for the user to press the non-existance switch. Rebooting now resolves the problem because the ESC_CAL parameter is reset to zero regardless of whether the calibration completes or not.
This commit is contained in:
parent
5915439c4e
commit
b0311c4ef3
|
@ -125,6 +125,9 @@ void Copter::esc_calibration_auto()
|
||||||
#if FRAME_CONFIG != HELI_FRAME
|
#if FRAME_CONFIG != HELI_FRAME
|
||||||
bool printed_msg = false;
|
bool printed_msg = false;
|
||||||
|
|
||||||
|
// clear esc flag for next time
|
||||||
|
g.esc_calibrate.set_and_save(ESCCAL_NONE);
|
||||||
|
|
||||||
if (motors->get_pwm_type() >= AP_Motors::PWM_TYPE_ONESHOT) {
|
if (motors->get_pwm_type() >= AP_Motors::PWM_TYPE_ONESHOT) {
|
||||||
// run at full speed for oneshot ESCs (actually done on push)
|
// run at full speed for oneshot ESCs (actually done on push)
|
||||||
motors->set_update_rate(g.rc_speed);
|
motors->set_update_rate(g.rc_speed);
|
||||||
|
@ -169,9 +172,6 @@ void Copter::esc_calibration_auto()
|
||||||
// reduce throttle to minimum
|
// reduce throttle to minimum
|
||||||
motors->set_throttle_passthrough_for_esc_calibration(0.0f);
|
motors->set_throttle_passthrough_for_esc_calibration(0.0f);
|
||||||
|
|
||||||
// clear esc parameter
|
|
||||||
g.esc_calibrate.set_and_save(ESCCAL_NONE);
|
|
||||||
|
|
||||||
// block until we restart
|
// block until we restart
|
||||||
while(1) {
|
while(1) {
|
||||||
motors->set_throttle_passthrough_for_esc_calibration(0.0f);
|
motors->set_throttle_passthrough_for_esc_calibration(0.0f);
|
||||||
|
|
Loading…
Reference in New Issue