mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
AP_Compass: add and use AP_CUSTOMROTATIONS_ENABLED
also add to build_options.py
This commit is contained in:
parent
a836bd8583
commit
093deed610
@ -731,7 +731,7 @@ void Compass::init()
|
|||||||
|
|
||||||
// convert to new custom rotation method
|
// convert to new custom rotation method
|
||||||
// PARAMETER_CONVERSION - Added: Nov-2021
|
// PARAMETER_CONVERSION - Added: Nov-2021
|
||||||
#if !APM_BUILD_TYPE(APM_BUILD_AP_Periph)
|
#if AP_CUSTOMROTATIONS_ENABLED
|
||||||
for (StateIndex i(0); i<COMPASS_MAX_INSTANCES; i++) {
|
for (StateIndex i(0); i<COMPASS_MAX_INSTANCES; i++) {
|
||||||
if (_state[i].orientation != ROTATION_CUSTOM_OLD) {
|
if (_state[i].orientation != ROTATION_CUSTOM_OLD) {
|
||||||
continue;
|
continue;
|
||||||
@ -751,7 +751,7 @@ void Compass::init()
|
|||||||
}
|
}
|
||||||
break;
|
break;
|
||||||
}
|
}
|
||||||
#endif // !APM_BUILD_TYPE(APM_BUILD_AP_Periph)
|
#endif // AP_CUSTOMROTATIONS_ENABLED
|
||||||
|
|
||||||
#if COMPASS_MAX_INSTANCES > 1
|
#if COMPASS_MAX_INSTANCES > 1
|
||||||
// Look if there was a primary compass setup in previous version
|
// Look if there was a primary compass setup in previous version
|
||||||
|
Loading…
Reference in New Issue
Block a user