New issue
Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.
By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.
Already on GitHub? Sign in to your account
Compass Ordering Improvement #12629
Open
bugobliterator
wants to merge
7
commits into
ArduPilot:master
from
bugobliterator:pr-compass-ordering
base: master
+502
−234
Open
Compass Ordering Improvement #12629
Changes from all commits
Commits
Show all changes
7 commits
Select commit
Hold shift + click to select a range
863b304
Arducopter: Primary Compass is always serial# 0
bugobliterator 2b4d1a7
AP_Arming: Primary Compass is always at serial# 0
bugobliterator d8fc614
ArduCopter: add arming message for compass not detected but assigned
bugobliterator 6e5102a
AP_Arming: add arming message for compass not detected but assigned
bugobliterator 161fe2b
AP_NavEKF2: Primary compass is always at serial number 0
bugobliterator 31962c8
AP_NavEKF3: Primary compass is always at serial number 0
bugobliterator 22c056e
AP_Compass: modify compass driver to support consistent ordering and …
bugobliterator File filter...
Filter file types
Jump to…
Jump to file or symbol
Failed to load files and symbols.
@@ -384,7 +384,7 @@ bool AP_Arming::compass_checks(bool report) | ||
|
||
// avoid Compass::use_for_yaw(void) as it implicitly calls healthy() which can | ||
// incorrectly skip the remaining checks, pass the primary instance directly | ||
if (!_compass.use_for_yaw(_compass.get_primary())) { | ||
if (!_compass.use_for_yaw(0)) { | ||
tridge
Contributor
|
||
// compass use is disabled | ||
return true; | ||
} | ||
@@ -394,9 +394,12 @@ bool AP_Arming::compass_checks(bool report) | ||
return false; | ||
} | ||
// check compass learning is on or offsets have been set | ||
if (!_compass.learn_offsets_enabled() && !_compass.configured()) { | ||
check_failed(ARMING_CHECK_COMPASS, report, "Compass not calibrated"); | ||
return false; | ||
if (!_compass.learn_offsets_enabled()) { | ||
char failure_msg[50] = {}; | ||
if (!_compass.configured(failure_msg, ARRAY_SIZE(failure_msg))) { | ||
check_failed(ARMING_CHECK_COMPASS, report, "%s", failure_msg); | ||
return false; | ||
} | ||
} | ||
|
||
// check for unreasonable compass offsets | ||

Oops, something went wrong.
ProTip!
Use n and p to navigate between commits in a pull request.
Add this suggestion to a batch that can be applied as a single commit.
This suggestion is invalid because no changes were made to the code.
Suggestions cannot be applied while the pull request is closed.
Suggestions cannot be applied while viewing a subset of changes.
Only one suggestion per line can be applied in a batch.
Add this suggestion to a batch that can be applied as a single commit.
Applying suggestions on deleted lines is not supported.
You must change the existing code in this line in order to create a valid suggestion.
Outdated suggestions cannot be applied.
This suggestion has been applied or marked resolved.
Suggestions cannot be applied from pending reviews.
Suggestions cannot be applied on multi-line comments.
this seems to assume the first instance is the primary? Don't we need to lookup via a mapping between the PRI var and instance?