mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-01 21:48:28 -04:00
Plane: bug fix to Loiter after mission completes
This commit is contained in:
parent
acdaf561c8
commit
27969175d9
@ -1,12 +1,20 @@
|
||||
/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
|
||||
|
||||
// forward declaration of verify_command to keep compiler happy
|
||||
static bool verify_command(const AP_Mission::Mission_Command& cmd);
|
||||
|
||||
// called by update navigation at 10Hz
|
||||
// --------------------
|
||||
static void update_commands(void)
|
||||
{
|
||||
if(control_mode == AUTO) {
|
||||
if(home_is_set == true && mission.num_commands() > 1) {
|
||||
mission.update();
|
||||
if(mission.state() == AP_Mission::MISSION_RUNNING) {
|
||||
mission.update();
|
||||
}else if(mission.state() == AP_Mission::MISSION_COMPLETE) {
|
||||
// next_nav_command should have been set to MAV_CMD_NAV_LOITER_UNLIM by exit_mission
|
||||
verify_command(next_nav_command);
|
||||
}
|
||||
}
|
||||
}
|
||||
}
|
||||
|
Loading…
Reference in New Issue
Block a user