mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-25 18:18:49 -04:00
Auto_land update
This commit is contained in:
parent
beac2930c9
commit
de912b5054
@ -1609,8 +1609,8 @@ static void update_navigation()
|
|||||||
case RTL:
|
case RTL:
|
||||||
if((wp_distance <= g.waypoint_radius) || check_missed_wp()){
|
if((wp_distance <= g.waypoint_radius) || check_missed_wp()){
|
||||||
// if this value > 0, we are set to trigger auto_land after 30 seconds
|
// if this value > 0, we are set to trigger auto_land after 30 seconds
|
||||||
auto_land_timer = millis();
|
|
||||||
set_mode(LOITER);
|
set_mode(LOITER);
|
||||||
|
auto_land_timer = millis();
|
||||||
|
|
||||||
}else{
|
}else{
|
||||||
// calculates desired Yaw
|
// calculates desired Yaw
|
||||||
@ -1645,7 +1645,7 @@ static void update_navigation()
|
|||||||
if(auto_land_timer != 0 && (millis() - auto_land_timer) > 30000){
|
if(auto_land_timer != 0 && (millis() - auto_land_timer) > 30000){
|
||||||
// just to make sure we clear the timer
|
// just to make sure we clear the timer
|
||||||
auto_land_timer = 0;
|
auto_land_timer = 0;
|
||||||
set_mode(land);
|
set_mode(LAND);
|
||||||
}
|
}
|
||||||
|
|
||||||
// calculates the desired Roll and Pitch
|
// calculates the desired Roll and Pitch
|
||||||
|
Loading…
Reference in New Issue
Block a user