Copter: Tradheli to check rotor_runup_complete before allowing takeoff.

This commit is contained in:
Robert Lefebvre 2015-06-16 21:31:03 -04:00 committed by Randy Mackay
parent 48828a7834
commit 8891cd159a

View File

@ -43,10 +43,16 @@ void Copter::althold_run()
float target_climb_rate = get_pilot_desired_climb_rate(channel_throttle->control_in);
target_climb_rate = constrain_float(target_climb_rate, -g.pilot_velocity_z_max, g.pilot_velocity_z_max);
#if FRAME_CONFIG == HELI_FRAME
bool takeoff_triggered = (ap.land_complete && (channel_throttle->control_in > get_takeoff_trigger_throttle()) && motors.rotor_runup_complete());
#else
bool takeoff_triggered = (ap.land_complete && (channel_throttle->control_in > get_takeoff_trigger_throttle()));
#endif
// Alt Hold State Machine Determination
if(!ap.auto_armed || !motors.get_interlock()) {
althold_state = AltHold_Disarmed;
} else if (takeoff_state.running || (ap.land_complete && (channel_throttle->control_in > get_takeoff_trigger_throttle()))){
} else if (takeoff_state.running || takeoff_triggered){
althold_state = AltHold_Takeoff;
} else if (ap.land_complete){
althold_state = AltHold_Landed;