mirror of https://github.com/ArduPilot/ardupilot
GPS: use primary for Notification
This commit is contained in:
parent
7b4cd9ee37
commit
a8a6368f05
|
@ -334,9 +334,6 @@ AP_GPS::update(void)
|
|||
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
|
||||
// work out which GPS is the primary, and how many sensors we have
|
||||
for (uint8_t i=0; i<GPS_MAX_INSTANCES; i++) {
|
||||
|
@ -366,8 +363,11 @@ AP_GPS::update(void)
|
|||
}
|
||||
}
|
||||
#else
|
||||
primary_instance=0;
|
||||
num_instances = 1;
|
||||
#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;
|
||||
}
|
||||
|
||||
/*
|
||||
|
|
Loading…
Reference in New Issue