mirror of https://github.com/ArduPilot/ardupilot
AP_ExternalAHRS: correct compilation when baro and compass externalahrs disabled
This commit is contained in:
parent
79eeb7b461
commit
7898d6f107
|
@ -466,13 +466,17 @@ bool AP_ExternalAHRS_InertialLabs::check_uart()
|
|||
last_gps_ms = now_ms;
|
||||
}
|
||||
}
|
||||
#if AP_BARO_EXTERNALAHRS_ENABLED
|
||||
if (GOT_MSG(BARO_DATA) &&
|
||||
GOT_MSG(TEMPERATURE)) {
|
||||
AP::baro().handle_external(baro_data);
|
||||
}
|
||||
#endif
|
||||
#if AP_COMPASS_EXTERNALAHRS_ENABLED
|
||||
if (GOT_MSG(MAG_DATA)) {
|
||||
AP::compass().handle_external(mag_data);
|
||||
}
|
||||
#endif
|
||||
#if AP_AIRSPEED_EXTERNAL_ENABLED && (APM_BUILD_COPTER_OR_HELI || APM_BUILD_TYPE(APM_BUILD_ArduPlane))
|
||||
// only on plane and copter as others do not link AP_Airspeed
|
||||
if (GOT_MSG(DIFFERENTIAL_PRESSURE) &&
|
||||
|
|
Loading…
Reference in New Issue