Plane: bug fix for setting flight_stage based on current command

This commit is contained in:
Randy Mackay 2014-03-10 17:35:13 +09:00
parent c4364a8ff5
commit 802ab79c84
1 changed files with 2 additions and 9 deletions

View File

@ -460,13 +460,6 @@ static uint8_t ground_start_count = 5;
// true if we have a position estimate from AHRS
static bool have_position;
////////////////////////////////////////////////////////////////////////////////
// Location & Navigation
////////////////////////////////////////////////////////////////////////////////
// There may be two active commands in Auto mode.
// This is the command type (eg navigate to waypoint) of the active navigation command
static uint8_t nav_command_ID = NO_COMMAND;
////////////////////////////////////////////////////////////////////////////////
// Airspeed
@ -1396,9 +1389,9 @@ static void update_alt()
if (control_mode==AUTO) {
if (takeoff_complete == false) {
flight_stage = AP_SpdHgtControl::FLIGHT_TAKEOFF;
} else if (nav_command_ID == MAV_CMD_NAV_LAND && land_complete == true) {
} else if (mission.get_current_nav_cmd().id == MAV_CMD_NAV_LAND && land_complete == true) {
flight_stage = AP_SpdHgtControl::FLIGHT_LAND_FINAL;
} else if (nav_command_ID == MAV_CMD_NAV_LAND) {
} else if (mission.get_current_nav_cmd().id == MAV_CMD_NAV_LAND) {
flight_stage = AP_SpdHgtControl::FLIGHT_LAND_APPROACH;
}
}