mirror of https://github.com/ArduPilot/ardupilot
Copter: Heli Semantic Change. Motor Runup to Rotor Runup.
This commit is contained in:
parent
d24664ccf9
commit
80b4ca99f8
|
@ -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;
|
||||
|
|
|
@ -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
|
||||
|
|
Loading…
Reference in New Issue