Plane: move `have_autoenabled_fences` to be private in `ModeTakeoff`

This commit is contained in:
Iampete1 2024-07-25 00:14:28 +01:00 committed by Andrew Tridgell
parent 535f806c96
commit 55f51eabe8
3 changed files with 9 additions and 6 deletions

View File

@ -250,9 +250,6 @@ private:
// are we currently in long failsafe but have postponed it in MODE TAKEOFF until min level alt is reached
bool long_failsafe_pending;
//flag that we have already called autoenable fences once in MODE TAKEOFF
bool have_autoenabled_fences;
// GCS selection
GCS_Plane _gcs; // avoid using this; use gcs()

View File

@ -816,6 +816,12 @@ protected:
Location start_loc;
bool _enter() override;
private:
// flag that we have already called autoenable fences once in MODE TAKEOFF
bool have_autoenabled_fences;
};
#if HAL_SOARING_ENABLED

View File

@ -63,7 +63,7 @@ ModeTakeoff::ModeTakeoff() :
bool ModeTakeoff::_enter()
{
takeoff_mode_setup = false;
plane.have_autoenabled_fences = false;
have_autoenabled_fences = false;
return true;
}
@ -155,9 +155,9 @@ void ModeTakeoff::update()
} else {
if ((altitude_cm >= alt * 100 - 200)) { //within 2m of TKOFF_ALT, or above and loitering
#if AP_FENCE_ENABLED
if (!plane.have_autoenabled_fences) {
if (!have_autoenabled_fences) {
plane.fence.auto_enable_fence_after_takeoff();
plane.have_autoenabled_fences = true;
have_autoenabled_fences = true;
}
#endif
plane.calc_nav_roll();