mirror of https://github.com/ArduPilot/ardupilot
Copter: fixed issue with crash check define
used in a multiplication, needs parantheses
This commit is contained in:
parent
dc2e04dc85
commit
ab2df43364
|
@ -3,7 +3,7 @@
|
||||||
// Code to detect a crash main ArduCopter code
|
// Code to detect a crash main ArduCopter code
|
||||||
#if PARACHUTE == ENABLED
|
#if PARACHUTE == ENABLED
|
||||||
// CRASH_CHECK_TRIGGER_SEC should be grater than CHUTE_TIMEOUT, to prevent disarming without deploying parachute
|
// 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
|
#else
|
||||||
#define CRASH_CHECK_TRIGGER_SEC 2 // 2 seconds inverted indicates a crash
|
#define CRASH_CHECK_TRIGGER_SEC 2 // 2 seconds inverted indicates a crash
|
||||||
#endif
|
#endif
|
||||||
|
|
Loading…
Reference in New Issue