mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-01 13:38:38 -04:00
GPS: init primary_instance to zero
This commit is contained in:
parent
010d267376
commit
8a776f8ff8
@ -87,8 +87,8 @@ void AP_GPS::init(DataFlash_Class *dataflash)
|
||||
{
|
||||
_DataFlash = dataflash;
|
||||
hal.uartB->begin(38400UL, 256, 16);
|
||||
#if GPS_MAX_INSTANCES > 1
|
||||
primary_instance = 0;
|
||||
#if GPS_MAX_INSTANCES > 1
|
||||
if (hal.uartE != NULL) {
|
||||
hal.uartE->begin(38400UL, 256, 16);
|
||||
}
|
||||
@ -378,7 +378,6 @@ 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
|
||||
|
Loading…
Reference in New Issue
Block a user