commands_process.pde: Bug fix 427. By default, the copter would land after an AUTO mission. Updated to check for valid approach altitude at end of mission.

This commit is contained in:
Adam M Rivera 2012-06-29 21:41:56 -05:00
parent 136c03c3c0
commit 61baa666c4

View File

@ -64,7 +64,8 @@ static void update_commands()
if (land_complete == true){
// we will disarm the motors after landing.
} else {
set_mode(LAND);
// If the approach altitude is valid (above 1m), do approach, else land
set_mode(((g.rtl_approach_alt >= 1) ? APPROACH : LAND));
}
}
}