From 686b9322cd0c5f39f1ccac3778cec4b82fd97d04 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Wed, 1 Jan 2020 09:08:19 +1100 Subject: [PATCH] AP_Math: define ROTATION_MAX_AUTO_ROTATION we don't want to use ROTATION_PITCH_7 in our auto rotation mix, as it is too close to level --- libraries/AP_Math/rotations.h | 4 ++++ 1 file changed, 4 insertions(+) diff --git a/libraries/AP_Math/rotations.h b/libraries/AP_Math/rotations.h index 3fd3a36c46..efa9ea7aed 100644 --- a/libraries/AP_Math/rotations.h +++ b/libraries/AP_Math/rotations.h @@ -76,6 +76,10 @@ enum Rotation : uint8_t { ROTATION_MAX, ROTATION_CUSTOM = 100, }; + +// maximum rotation that will be used for auto-detection +#define ROTATION_MAX_AUTO_ROTATION ROTATION_ROLL_90_PITCH_315 + /* Here are the same values in a form sutable for a @Values attribute in auto documentation: