mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 14:38:30 -04:00
Copter: move set_land_complete_maybe to landing_detector.cpp
This commit is contained in:
parent
b139dfedae
commit
42c202a08f
@ -96,21 +96,6 @@ void Copter::set_failsafe_gcs(bool b)
|
||||
|
||||
// ---------------------------------------------
|
||||
|
||||
// set land complete maybe flag
|
||||
void Copter::set_land_complete_maybe(bool b)
|
||||
{
|
||||
// if no change, exit immediately
|
||||
if (ap.land_complete_maybe == b)
|
||||
return;
|
||||
|
||||
if (b) {
|
||||
Log_Write_Event(DATA_LAND_COMPLETE_MAYBE);
|
||||
}
|
||||
ap.land_complete_maybe = b;
|
||||
}
|
||||
|
||||
// ---------------------------------------------
|
||||
|
||||
void Copter::set_pre_arm_check(bool b)
|
||||
{
|
||||
if(ap.pre_arm_check != b) {
|
||||
|
@ -77,6 +77,19 @@ void Copter::set_land_complete(bool b)
|
||||
ap.land_complete = b;
|
||||
}
|
||||
|
||||
// set land complete maybe flag
|
||||
void Copter::set_land_complete_maybe(bool b)
|
||||
{
|
||||
// if no change, exit immediately
|
||||
if (ap.land_complete_maybe == b)
|
||||
return;
|
||||
|
||||
if (b) {
|
||||
Log_Write_Event(DATA_LAND_COMPLETE_MAYBE);
|
||||
}
|
||||
ap.land_complete_maybe = b;
|
||||
}
|
||||
|
||||
// update_throttle_thr_mix - sets motors throttle_low_comp value depending upon vehicle state
|
||||
// low values favour pilot/autopilot throttle over attitude control, high values favour attitude control over throttle
|
||||
// has no effect when throttle is above hover throttle
|
||||
|
Loading…
Reference in New Issue
Block a user