Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Plane: move have_autoenabled_fences to be private in ModeTakeoff #27638

Merged
merged 1 commit into from
Jul 29, 2024
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
3 changes: 0 additions & 3 deletions ArduPlane/Plane.h
Original file line number Diff line number Diff line change
Expand Up @@ -250,9 +250,6 @@ class Plane : public AP_Vehicle {

// 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()
Expand Down
6 changes: 6 additions & 0 deletions ArduPlane/mode.h
Original file line number Diff line number Diff line change
Expand Up @@ -816,6 +816,12 @@ class ModeTakeoff: public Mode
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
Expand Down
6 changes: 3 additions & 3 deletions ArduPlane/mode_takeoff.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -63,7 +63,7 @@ ModeTakeoff::ModeTakeoff() :
bool ModeTakeoff::_enter()
{
takeoff_mode_setup = false;
plane.have_autoenabled_fences = false;
have_autoenabled_fences = false;

return true;
}
Expand Down Expand Up @@ -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();
Expand Down
Loading