mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
Plane: move have_autoenabled_fences
to be private in ModeTakeoff
This commit is contained in:
parent
535f806c96
commit
55f51eabe8
@ -250,9 +250,6 @@ private:
|
|||||||
|
|
||||||
// are we currently in long failsafe but have postponed it in MODE TAKEOFF until min level alt is reached
|
// are we currently in long failsafe but have postponed it in MODE TAKEOFF until min level alt is reached
|
||||||
bool long_failsafe_pending;
|
bool long_failsafe_pending;
|
||||||
|
|
||||||
//flag that we have already called autoenable fences once in MODE TAKEOFF
|
|
||||||
bool have_autoenabled_fences;
|
|
||||||
|
|
||||||
// GCS selection
|
// GCS selection
|
||||||
GCS_Plane _gcs; // avoid using this; use gcs()
|
GCS_Plane _gcs; // avoid using this; use gcs()
|
||||||
|
@ -816,6 +816,12 @@ protected:
|
|||||||
Location start_loc;
|
Location start_loc;
|
||||||
|
|
||||||
bool _enter() override;
|
bool _enter() override;
|
||||||
|
|
||||||
|
private:
|
||||||
|
|
||||||
|
// flag that we have already called autoenable fences once in MODE TAKEOFF
|
||||||
|
bool have_autoenabled_fences;
|
||||||
|
|
||||||
};
|
};
|
||||||
|
|
||||||
#if HAL_SOARING_ENABLED
|
#if HAL_SOARING_ENABLED
|
||||||
|
@ -63,7 +63,7 @@ ModeTakeoff::ModeTakeoff() :
|
|||||||
bool ModeTakeoff::_enter()
|
bool ModeTakeoff::_enter()
|
||||||
{
|
{
|
||||||
takeoff_mode_setup = false;
|
takeoff_mode_setup = false;
|
||||||
plane.have_autoenabled_fences = false;
|
have_autoenabled_fences = false;
|
||||||
|
|
||||||
return true;
|
return true;
|
||||||
}
|
}
|
||||||
@ -155,9 +155,9 @@ void ModeTakeoff::update()
|
|||||||
} else {
|
} else {
|
||||||
if ((altitude_cm >= alt * 100 - 200)) { //within 2m of TKOFF_ALT, or above and loitering
|
if ((altitude_cm >= alt * 100 - 200)) { //within 2m of TKOFF_ALT, or above and loitering
|
||||||
#if AP_FENCE_ENABLED
|
#if AP_FENCE_ENABLED
|
||||||
if (!plane.have_autoenabled_fences) {
|
if (!have_autoenabled_fences) {
|
||||||
plane.fence.auto_enable_fence_after_takeoff();
|
plane.fence.auto_enable_fence_after_takeoff();
|
||||||
plane.have_autoenabled_fences = true;
|
have_autoenabled_fences = true;
|
||||||
}
|
}
|
||||||
#endif
|
#endif
|
||||||
plane.calc_nav_roll();
|
plane.calc_nav_roll();
|
||||||
|
Loading…
Reference in New Issue
Block a user