Skip to content

Commit

Permalink
Copter: add a Mode method to disable crash check
Browse files Browse the repository at this point in the history
prevents looking for specific modes in the crash checker
  • Loading branch information
peterbarker authored and rmackay9 committed Jul 30, 2024
1 parent 9397ece commit 6881f42
Show file tree
Hide file tree
Showing 2 changed files with 5 additions and 2 deletions.
4 changes: 2 additions & 2 deletions ArduCopter/crash_check.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -42,7 +42,7 @@ void Copter::crash_check()
}

// return immediately if we are not in an angle stabilize flight mode or we are flipping
if (flightmode->mode_number() == Mode::Number::ACRO || flightmode->mode_number() == Mode::Number::FLIP) {
if (flightmode->disable_crash_check()) {
crash_counter = 0;
return;
}
Expand Down Expand Up @@ -273,7 +273,7 @@ void Copter::parachute_check()
}

// return immediately if we are not in an angle stabilize flight mode or we are flipping
if (flightmode->mode_number() == Mode::Number::ACRO || flightmode->mode_number() == Mode::Number::FLIP) {
if (flightmode->disable_crash_check()) {
control_loss_count = 0;
return;
}
Expand Down
3 changes: 3 additions & 0 deletions ArduCopter/mode.h
Original file line number Diff line number Diff line change
Expand Up @@ -128,6 +128,7 @@ class Mode {
virtual bool allows_save_trim() const { return false; }
virtual bool allows_autotune() const { return false; }
virtual bool allows_flip() const { return false; }
virtual bool disable_crash_check() const { return false; }

#if FRAME_CONFIG == HELI_FRAME
virtual bool allows_inverted() const { return false; };
Expand Down Expand Up @@ -420,6 +421,7 @@ class ModeAcro : public Mode {
void air_mode_aux_changed();
bool allows_save_trim() const override { return true; }
bool allows_flip() const override { return true; }
bool disable_crash_check() const override { return true; }

protected:

Expand Down Expand Up @@ -911,6 +913,7 @@ class ModeFlip : public Mode {
bool has_manual_throttle() const override { return false; }
bool allows_arming(AP_Arming::Method method) const override { return false; };
bool is_autopilot() const override { return false; }
bool disable_crash_check() const override { return true; }

protected:

Expand Down

0 comments on commit 6881f42

Please sign in to comment.