fixed logic bug to make a copter loiter after the mission is ended.
This commit is contained in:
Jason Short 2012-07-03 17:38:50 -07:00
parent a143e7bef6
commit cc51d497c6
1 changed files with 3 additions and 3 deletions

View File

@ -65,11 +65,11 @@ static void update_commands()
// we will disarm the motors after landing. // we will disarm the motors after landing.
} else { } else {
// If the approach altitude is valid (above 1m), do approach, else land // If the approach altitude is valid (above 1m), do approach, else land
if(g.rtl_approach_alt >= 1){ if(g.rtl_approach_alt == 0){
set_mode(LAND);
}else{
set_mode(LOITER); set_mode(LOITER);
set_new_altitude(g.rtl_approach_alt); set_new_altitude(g.rtl_approach_alt);
}else{
set_mode(LAND);
} }
} }
} }