Browse Source

AP_GPS: log GPS primary change event in GPS library

gps-1.3.1
Peter Barker 4 years ago committed by Peter Barker
parent
commit
c9699d7ce4
  1. 8
      libraries/AP_GPS/AP_GPS.cpp

8
libraries/AP_GPS/AP_GPS.cpp

@ -925,7 +925,15 @@ void AP_GPS::update(void) @@ -925,7 +925,15 @@ void AP_GPS::update(void)
}
}
#if HAL_LOGGING_ENABLED
const uint8_t old_primary = primary_instance;
#endif
update_primary();
#if HAL_LOGGING_ENABLED
if (primary_instance != old_primary) {
AP::logger().Write_Event(LogEvent::GPS_PRIMARY_CHANGED);
}
#endif
#ifndef HAL_BUILD_AP_PERIPH
// update notify with gps status. We always base this on the primary_instance

Loading…
Cancel
Save