Browse Source

AP_Baro: fix externalAHRS detection

'A = B >= C' kind. The expression is calculated as following: 'A = (B >= C)'
zr-v5.1
Pierre Kancir 4 years ago committed by Randy Mackay
parent
commit
3043ab6b01
  1. 3
      libraries/AP_Baro/AP_Baro.cpp

3
libraries/AP_Baro/AP_Baro.cpp

@ -531,7 +531,8 @@ void AP_Baro::init(void) @@ -531,7 +531,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…
Cancel
Save