Copter : Land submode - Check for GPS 3D Fix instead of checking for available home position

This commit is contained in:
Olivier-ADLER 2013-06-01 17:41:37 +02:00 committed by Randy Mackay
parent 18e566ccc5
commit 68470c9176

View File

@ -434,7 +434,7 @@ static void set_mode(uint8_t mode)
case LAND:
// To-Do: it is messy to set manual_attitude here because the do_land function is reponsible for setting the roll_pitch_mode
if( ap.home_is_set ) {
if( g_gps->status() == GPS::GPS_OK_FIX_3D ) {
// switch to loiter if we have gps
ap.manual_attitude = false;
}else{