mirror of https://github.com/ArduPilot/ardupilot
Forced Faildafe throttle mode to throttle Auto
This commit is contained in:
parent
57c3405658
commit
056a08d838
|
@ -450,7 +450,7 @@ static void set_mode(byte mode)
|
||||||
control_mode = constrain(control_mode, 0, NUM_MODES - 1);
|
control_mode = constrain(control_mode, 0, NUM_MODES - 1);
|
||||||
|
|
||||||
// used to stop fly_aways
|
// used to stop fly_aways
|
||||||
motor_auto_armed = (g.rc_3.control_in > 0) || failsafe;
|
motor_auto_armed = (g.rc_3.control_in > 0);
|
||||||
|
|
||||||
// clearing value used in interactive alt hold
|
// clearing value used in interactive alt hold
|
||||||
manual_boost = 0;
|
manual_boost = 0;
|
||||||
|
@ -458,6 +458,7 @@ static void set_mode(byte mode)
|
||||||
// do not auto_land if we are leaving RTL
|
// do not auto_land if we are leaving RTL
|
||||||
auto_land_timer = 0;
|
auto_land_timer = 0;
|
||||||
|
|
||||||
|
// debug to Serial terminal
|
||||||
Serial.println(flight_mode_strings[control_mode]);
|
Serial.println(flight_mode_strings[control_mode]);
|
||||||
|
|
||||||
// report the GPS and Motor arming status
|
// report the GPS and Motor arming status
|
||||||
|
@ -550,6 +551,14 @@ static void set_mode(byte mode)
|
||||||
break;
|
break;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
if(failsafe){
|
||||||
|
// this is to allow us to fly home without interactive throttle control
|
||||||
|
throttle_mode = THROTTLE_AUTO;
|
||||||
|
// does not wait for us to be in high throttle, since the
|
||||||
|
// Receiver will be outputting low throttle
|
||||||
|
motor_auto_armed = true;
|
||||||
|
}
|
||||||
|
|
||||||
if(throttle_mode == THROTTLE_MANUAL){
|
if(throttle_mode == THROTTLE_MANUAL){
|
||||||
// reset all of the throttle iterms
|
// reset all of the throttle iterms
|
||||||
g.pi_alt_hold.reset_I();
|
g.pi_alt_hold.reset_I();
|
||||||
|
@ -595,7 +604,6 @@ static void set_failsafe(boolean mode)
|
||||||
// We've lost radio contact
|
// We've lost radio contact
|
||||||
// ------------------------
|
// ------------------------
|
||||||
failsafe_on_event();
|
failsafe_on_event();
|
||||||
|
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
Loading…
Reference in New Issue