mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-11 10:28:29 -04:00
ArduCopter: Added code to prevent mode from switching to APPROACH on every loiter.
This commit is contained in:
parent
b891622210
commit
baf8218b58
@ -1814,17 +1814,19 @@ static void update_navigation()
|
|||||||
wp_control = LOITER_MODE;
|
wp_control = LOITER_MODE;
|
||||||
}
|
}
|
||||||
|
|
||||||
// If we have a safe approach alt set and we have been loitering for 20 seconds(default), begin approach
|
if(loiter_timer != 0){
|
||||||
if(g.rtl_approach_alt >= 1 && (millis() - loiter_timer) > (RTL_APPROACH_DELAY * 1000)){
|
// If we have a safe approach alt set and we have been loitering for 20 seconds(default), begin approach
|
||||||
// just to make sure we clear the timer
|
if(g.rtl_approach_alt >= 1 && (millis() - loiter_timer) > (RTL_APPROACH_DELAY * 1000)){
|
||||||
loiter_timer = 0;
|
// just to make sure we clear the timer
|
||||||
set_mode(APPROACH);
|
loiter_timer = 0;
|
||||||
}
|
set_mode(APPROACH);
|
||||||
// Kick us out of loiter and begin landing if the loiter_timer is set
|
}
|
||||||
else if(loiter_timer != 0 && (millis() - loiter_timer) > (uint32_t)g.auto_land_timeout.get()){
|
// Kick us out of loiter and begin landing if the loiter_timer is set
|
||||||
// just to make sure we clear the timer
|
else if((millis() - loiter_timer) > (uint32_t)g.auto_land_timeout.get()){
|
||||||
loiter_timer = 0;
|
// just to make sure we clear the timer
|
||||||
set_mode(LAND);
|
loiter_timer = 0;
|
||||||
|
set_mode(LAND);
|
||||||
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
// calculates the desired Roll and Pitch
|
// calculates the desired Roll and Pitch
|
||||||
|
Loading…
Reference in New Issue
Block a user