mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-22 07:44:03 -04:00
Tools: add documentation for SIM_ENGINE_FAIL and SIM_ENGINE_MUL
This commit is contained in:
parent
93704c573c
commit
3c1021d208
@ -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->disable_crash_check()) {
|
if (!flightmode->crash_check_enabled()) {
|
||||||
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->disable_crash_check()) {
|
if (!flightmode->crash_check_enabled()) {
|
||||||
control_loss_count = 0;
|
control_loss_count = 0;
|
||||||
return;
|
return;
|
||||||
}
|
}
|
||||||
|
@ -128,7 +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; }
|
virtual bool crash_check_enabled() const { return true; }
|
||||||
|
|
||||||
#if FRAME_CONFIG == HELI_FRAME
|
#if FRAME_CONFIG == HELI_FRAME
|
||||||
virtual bool allows_inverted() const { return false; };
|
virtual bool allows_inverted() const { return false; };
|
||||||
@ -421,7 +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; }
|
bool crash_check_enabled() const override { return false; }
|
||||||
|
|
||||||
protected:
|
protected:
|
||||||
|
|
||||||
@ -913,7 +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; }
|
bool crash_check_enabled() const override { return false; }
|
||||||
|
|
||||||
protected:
|
protected:
|
||||||
|
|
||||||
|
@ -2441,8 +2441,6 @@ class TestSuite(ABC):
|
|||||||
"SIM_DRIFT_SPEED",
|
"SIM_DRIFT_SPEED",
|
||||||
"SIM_DRIFT_TIME",
|
"SIM_DRIFT_TIME",
|
||||||
"SIM_EFI_TYPE",
|
"SIM_EFI_TYPE",
|
||||||
"SIM_ENGINE_FAIL",
|
|
||||||
"SIM_ENGINE_MUL",
|
|
||||||
"SIM_ESC_ARM_RPM",
|
"SIM_ESC_ARM_RPM",
|
||||||
"SIM_FTOWESC_ENA",
|
"SIM_FTOWESC_ENA",
|
||||||
"SIM_FTOWESC_POW",
|
"SIM_FTOWESC_POW",
|
||||||
|
Loading…
Reference in New Issue
Block a user