Copter: fixed issue with crash check define

used in a multiplication, needs parantheses
This commit is contained in:
Andrew Tridgell 2024-08-03 07:26:26 +10:00
parent dc2e04dc85
commit ab2df43364
1 changed files with 1 additions and 1 deletions

View File

@ -3,7 +3,7 @@
// Code to detect a crash main ArduCopter code
#if PARACHUTE == ENABLED
// CRASH_CHECK_TRIGGER_SEC should be grater than CHUTE_TIMEOUT, to prevent disarming without deploying parachute
#define CRASH_CHECK_TRIGGER_SEC parachute.get_chute_timeout() + 1.0f
#define CRASH_CHECK_TRIGGER_SEC (parachute.get_chute_timeout() + 1.0)
#else
#define CRASH_CHECK_TRIGGER_SEC 2 // 2 seconds inverted indicates a crash
#endif