mirror of https://github.com/ArduPilot/ardupilot
Copter: rename land_maybe_complete function
This commit is contained in:
parent
5f909f1a73
commit
93dbfd009e
|
@ -287,8 +287,8 @@ static void auto_land_run()
|
|||
return;
|
||||
}
|
||||
|
||||
// init loiter targets when maybe landed
|
||||
if(land_maybe_complete()) {
|
||||
// relax loiter targets if we might be landed
|
||||
if (land_complete_maybe()) {
|
||||
wp_nav.loiter_soften_for_landing();
|
||||
}
|
||||
|
||||
|
|
|
@ -74,7 +74,7 @@ static void land_gps_run()
|
|||
}
|
||||
|
||||
// relax loiter target if we might be landed
|
||||
if(land_maybe_complete()) {
|
||||
if (land_complete_maybe()) {
|
||||
wp_nav.loiter_soften_for_landing();
|
||||
}
|
||||
|
||||
|
@ -192,8 +192,8 @@ static float get_throttle_land()
|
|||
}
|
||||
}
|
||||
|
||||
// land_maybe_complete - return true if we may have landed (used to reset loiter targets during landing)
|
||||
static bool land_maybe_complete()
|
||||
// land_complete_maybe - return true if we may have landed (used to reset loiter targets during landing)
|
||||
static bool land_complete_maybe()
|
||||
{
|
||||
return (ap.land_complete || ap.land_complete_maybe);
|
||||
}
|
||||
|
|
|
@ -69,7 +69,7 @@ static void loiter_run()
|
|||
}
|
||||
|
||||
// relax loiter target if we might be landed
|
||||
if (land_maybe_complete()) {
|
||||
if (land_complete_maybe()) {
|
||||
wp_nav.loiter_soften_for_landing();
|
||||
}
|
||||
|
||||
|
|
|
@ -184,7 +184,7 @@ static void poshold_run()
|
|||
}
|
||||
|
||||
// relax loiter target if we might be landed
|
||||
if(land_maybe_complete()) {
|
||||
if (land_complete_maybe()) {
|
||||
wp_nav.loiter_soften_for_landing();
|
||||
}
|
||||
|
||||
|
|
|
@ -350,7 +350,7 @@ static void rtl_land_run()
|
|||
}
|
||||
|
||||
// relax loiter target if we might be landed
|
||||
if(land_maybe_complete()) {
|
||||
if (land_complete_maybe()) {
|
||||
wp_nav.loiter_soften_for_landing();
|
||||
}
|
||||
|
||||
|
|
Loading…
Reference in New Issue