Skip to content
Snippets Groups Projects
Commit a8a6368f authored by Benoit PEREIRA DA SILVA's avatar Benoit PEREIRA DA SILVA Committed by Randy Mackay
Browse files

GPS: use primary for Notification

parent 7b4cd9ee
No related branches found
No related tags found
No related merge requests found
...@@ -334,9 +334,6 @@ AP_GPS::update(void) ...@@ -334,9 +334,6 @@ AP_GPS::update(void)
update_instance(i); update_instance(i);
} }
// update notify with gps status. We always base this on the first GPS
AP_Notify::flags.gps_status = state[0].status;
#if GPS_MAX_INSTANCES > 1 #if GPS_MAX_INSTANCES > 1
// work out which GPS is the primary, and how many sensors we have // work out which GPS is the primary, and how many sensors we have
for (uint8_t i=0; i<GPS_MAX_INSTANCES; i++) { for (uint8_t i=0; i<GPS_MAX_INSTANCES; i++) {
...@@ -366,8 +363,11 @@ AP_GPS::update(void) ...@@ -366,8 +363,11 @@ AP_GPS::update(void)
} }
} }
#else #else
primary_instance=0;
num_instances = 1; num_instances = 1;
#endif // GPS_MAX_INSTANCES #endif // GPS_MAX_INSTANCES
// update notify with gps status. We always base this on the primary_instance
AP_Notify::flags.gps_status = state[primary_instance].status;
} }
/* /*
......
0% Loading or .
You are about to add 0 people to the discussion. Proceed with caution.
Finish editing this message first!
Please register or to comment