mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 14:38:30 -04:00
Copter: add a Mode method to disable crash check
prevents looking for specific modes in the crash checker
This commit is contained in:
parent
9397ece55a
commit
6881f42cba
@ -42,7 +42,7 @@ void Copter::crash_check()
|
|||||||
}
|
}
|
||||||
|
|
||||||
// return immediately if we are not in an angle stabilize flight mode or we are flipping
|
// 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;
|
crash_counter = 0;
|
||||||
return;
|
return;
|
||||||
}
|
}
|
||||||
@ -273,7 +273,7 @@ void Copter::parachute_check()
|
|||||||
}
|
}
|
||||||
|
|
||||||
// return immediately if we are not in an angle stabilize flight mode or we are flipping
|
// 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;
|
control_loss_count = 0;
|
||||||
return;
|
return;
|
||||||
}
|
}
|
||||||
|
@ -128,6 +128,7 @@ public:
|
|||||||
virtual bool allows_save_trim() const { return false; }
|
virtual bool allows_save_trim() const { return false; }
|
||||||
virtual bool allows_autotune() const { return false; }
|
virtual bool allows_autotune() const { return false; }
|
||||||
virtual bool allows_flip() const { return false; }
|
virtual bool allows_flip() const { return false; }
|
||||||
|
virtual bool disable_crash_check() const { return false; }
|
||||||
|
|
||||||
#if FRAME_CONFIG == HELI_FRAME
|
#if FRAME_CONFIG == HELI_FRAME
|
||||||
virtual bool allows_inverted() const { return false; };
|
virtual bool allows_inverted() const { return false; };
|
||||||
@ -420,6 +421,7 @@ public:
|
|||||||
void air_mode_aux_changed();
|
void air_mode_aux_changed();
|
||||||
bool allows_save_trim() const override { return true; }
|
bool allows_save_trim() const override { return true; }
|
||||||
bool allows_flip() const override { return true; }
|
bool allows_flip() const override { return true; }
|
||||||
|
bool disable_crash_check() const override { return true; }
|
||||||
|
|
||||||
protected:
|
protected:
|
||||||
|
|
||||||
@ -911,6 +913,7 @@ public:
|
|||||||
bool has_manual_throttle() const override { return false; }
|
bool has_manual_throttle() const override { return false; }
|
||||||
bool allows_arming(AP_Arming::Method method) const override { return false; };
|
bool allows_arming(AP_Arming::Method method) const override { return false; };
|
||||||
bool is_autopilot() const override { return false; }
|
bool is_autopilot() const override { return false; }
|
||||||
|
bool disable_crash_check() const override { return true; }
|
||||||
|
|
||||||
protected:
|
protected:
|
||||||
|
|
||||||
|
Loading…
Reference in New Issue
Block a user