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
This commit is contained in:
Andrew Tridgell 2020-01-01 09:08:19 +11:00
parent ad9e6f02cd
commit 686b9322cd
1 changed files with 4 additions and 0 deletions

View File

@ -76,6 +76,10 @@ enum Rotation : uint8_t {
ROTATION_MAX, ROTATION_MAX,
ROTATION_CUSTOM = 100, 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 Here are the same values in a form sutable for a @Values attribute in
auto documentation: auto documentation: