Skip to content
Snippets Groups Projects
Commit 05e59f6f authored by Randy Mackay's avatar Randy Mackay
Browse files

ArduCopter: bug fix to LAND flight mode not actually landing if initiated from failsafe

An hidden bit of failsafe functionality in the set_mode function was
switching the throttle mode back to THROTTLE_AUTO instead of
THROTTLE_LAND
parent a1889222
No related branches found
No related tags found
No related merge requests found
......@@ -408,8 +408,8 @@ static void set_mode(byte mode)
// used to stop fly_aways
// set to false if we have low throttle
motors.auto_armed(g.rc_3.control_in > 0);
set_auto_armed(g.rc_3.control_in > 0);
motors.auto_armed(g.rc_3.control_in > 0 || ap.failsafe);
set_auto_armed(g.rc_3.control_in > 0 || ap.failsafe);
// if we change modes, we must clear landed flag
set_land_complete(false);
......@@ -570,17 +570,6 @@ static void set_mode(byte mode)
break;
}
if(ap.failsafe) {
// this is to allow us to fly home without interactive throttle control
set_throttle_mode(THROTTLE_AUTO);
ap.manual_throttle = false;
// does not wait for us to be in high throttle, since the
// Receiver will be outputting low throttle
motors.auto_armed(true);
set_auto_armed(true);
}
if(ap.manual_attitude) {
// We are under manual attitude control
// remove the navigation from roll and pitch command
......
0% Loading or .
You are about to add 0 people to the discussion. Proceed with caution.
Finish editing this message first!
Please register or to comment