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:fix auto fence enable in Mode Takeoff #25785

Closed
wants to merge 1 commit into from
Closed
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
1 change: 1 addition & 0 deletions ArduPlane/mode.h
Original file line number Diff line number Diff line change
Expand Up @@ -784,6 +784,7 @@ class ModeTakeoff: public Mode
AP_Int8 level_pitch;

bool takeoff_started;
bool have_auto_enabled_fence;
Location start_loc;

bool _enter() override;
Expand Down
12 changes: 8 additions & 4 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_started = false;

have_auto_enabled_fence = false;
return true;
}

Expand Down Expand Up @@ -138,9 +138,6 @@ void ModeTakeoff::update()

plane.set_flight_stage(AP_FixedWing::FlightStage::NORMAL);

#if AP_FENCE_ENABLED
plane.fence.auto_enable_fence_after_takeoff();
#endif
}

if (plane.flight_stage == AP_FixedWing::FlightStage::TAKEOFF) {
Expand All @@ -152,6 +149,13 @@ void ModeTakeoff::update()
plane.calc_nav_pitch();
plane.calc_throttle();
//check if in long failsafe, if it is recall long failsafe now to get fs action via events call
Copy link
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

This comment belongs with the bit of code under the addition.

Copy link
Collaborator Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

will fix

#if AP_FENCE_ENABLED
const uint16_t altitude = plane.relative_ground_altitude(false,true);
if (altitude >= alt && !have_auto_enabled_fence) {
Copy link
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

I think the standard loiter check can be used?

Suggested change
if (altitude >= alt && !have_auto_enabled_fence) {
if (plane.reached_loiter_target() && (loiter.reached_target_alt || loiter.unable_to_acheive_target_alt) && !have_auto_enabled_fence) {

Copy link
Collaborator Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

I will try it in SITL

plane.fence.auto_enable_fence_after_takeoff();
have_auto_enabled_fence = true;
}
#endif
if (plane.long_failsafe_pending) {
plane.long_failsafe_pending = false;
plane.failsafe_long_on_event(FAILSAFE_LONG, ModeReason::MODE_TAKEOFF_FAILSAFE);
Expand Down
Loading