diff --git a/APMrover2/crash_check.cpp b/APMrover2/crash_check.cpp index 10360f0c9e..d7b402ebfa 100644 --- a/APMrover2/crash_check.cpp +++ b/APMrover2/crash_check.cpp @@ -1,9 +1,9 @@ #include "Rover.h" // Code to detect a crash or block -#define CRASH_CHECK_TRIGGER_SEC 2 // 2 seconds blocked indicates a crash -#define CRASH_CHECK_THROTTLE_MIN 5.0f // vehicle must have a throttle greater that 5% to be considered crashed -#define CRASH_CHECK_VEL_MIN 0.08f // vehicle must have a velocity under 0.08 m/s or rad/s to be considered crashed +static const uint16_t CRASH_CHECK_TRIGGER_SEC = 2; // 2 seconds blocked indicates a crash +static const float CRASH_CHECK_THROTTLE_MIN = 5.0f; // vehicle must have a throttle greater that 5% to be considered crashed +static const float CRASH_CHECK_VEL_MIN = 0.08f; // vehicle must have a velocity under 0.08 m/s or rad/s to be considered crashed // crash_check - disarms motors if a crash or block has been detected // crashes are detected by the vehicle being static (no speed) for more than CRASH_CHECK_TRIGGER_SEC and motor are running