From 80b4ca99f8605903d8ac6bd921ebedfdfecdd660 Mon Sep 17 00:00:00 2001 From: Robert Lefebvre Date: Thu, 28 May 2015 17:28:55 -0400 Subject: [PATCH] Copter: Heli Semantic Change. Motor Runup to Rotor Runup. --- ArduCopter/heli.pde | 2 +- ArduCopter/system.pde | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/ArduCopter/heli.pde b/ArduCopter/heli.pde index de0f65a6f3..0f48d09482 100644 --- a/ArduCopter/heli.pde +++ b/ArduCopter/heli.pde @@ -38,7 +38,7 @@ static int16_t get_pilot_desired_collective(int16_t control_in) // should be called at 50hz static void check_dynamic_flight(void) { - if (!motors.armed() || !motors.motor_runup_complete() || + if (!motors.armed() || !motors.rotor_runup_complete() || control_mode == LAND || (control_mode==RTL && rtl_state == RTL_Land) || (control_mode == AUTO && auto_mode == Auto_Land)) { heli_dynamic_flight_counter = 0; heli_flags.dynamic_flight = false; diff --git a/ArduCopter/system.pde b/ArduCopter/system.pde index facbea5192..916549a513 100644 --- a/ArduCopter/system.pde +++ b/ArduCopter/system.pde @@ -366,7 +366,7 @@ static void update_auto_armed() #if FRAME_CONFIG == HELI_FRAME // for tradheli if motors are armed and throttle is above zero and the motor is started, auto_armed should be true - if(motors.armed() && !ap.throttle_zero && motors.motor_runup_complete()) { + if(motors.armed() && !ap.throttle_zero && motors.rotor_runup_complete()) { set_auto_armed(true); } #else