mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-31 04:58:30 -04:00
AP_Baro: fix externalAHRS detection
'A = B >= C' kind. The expression is calculated as following: 'A = (B >= C)'
This commit is contained in:
parent
4481bc6147
commit
ae11353d81
@ -537,7 +537,8 @@ void AP_Baro::init(void)
|
||||
#endif
|
||||
|
||||
#if HAL_EXTERNAL_AHRS_ENABLED
|
||||
if (int8_t serial_port = AP::externalAHRS().get_port() >= 0) {
|
||||
const int8_t serial_port = AP::externalAHRS().get_port();
|
||||
if (serial_port >= 0) {
|
||||
ADD_BACKEND(new AP_Baro_ExternalAHRS(*this, serial_port));
|
||||
}
|
||||
#endif
|
||||
|
Loading…
Reference in New Issue
Block a user