mirror of https://github.com/ArduPilot/ardupilot
Copter: esc cal startup check moved outside rc output init
this ensures we don't accidentally enter esc calibration during motor test
This commit is contained in:
parent
f79a3100d0
commit
eb433508f1
|
@ -44,7 +44,7 @@ void Copter::init_rc_in()
|
|||
ap.throttle_zero = true;
|
||||
}
|
||||
|
||||
// init_rc_out -- initialise motors and check if pilot wants to perform ESC calibration
|
||||
// init_rc_out -- initialise motors
|
||||
void Copter::init_rc_out()
|
||||
{
|
||||
motors->set_loop_rate(scheduler.get_loop_rate_hz());
|
||||
|
@ -74,9 +74,6 @@ void Copter::init_rc_out()
|
|||
uint16_t safety_ignore_mask = (~copter.motors->get_motor_mask()) & 0x3FFF;
|
||||
BoardConfig.set_default_safety_ignore_mask(safety_ignore_mask);
|
||||
#endif
|
||||
|
||||
// check if we should enter esc calibration mode
|
||||
esc_calibration_startup_check();
|
||||
}
|
||||
|
||||
|
||||
|
|
|
@ -117,6 +117,9 @@ void Copter::init_ardupilot()
|
|||
// sets up motors and output to escs
|
||||
init_rc_out();
|
||||
|
||||
// check if we should enter esc calibration mode
|
||||
esc_calibration_startup_check();
|
||||
|
||||
// motors initialised so parameters can be sent
|
||||
ap.initialised_params = true;
|
||||
|
||||
|
|
Loading…
Reference in New Issue