mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-22 07:44:03 -04:00
AP_GPS: use default case for sending blob
This structure avoids a compiler warning that a statement isn't reachable when all backends are compiled out.
This commit is contained in:
parent
945e342001
commit
cd6b1b2667
@ -591,6 +591,8 @@ void AP_GPS::send_blob_start(uint8_t instance)
|
||||
#endif // AP_GPS_NMEA_ENABLED
|
||||
|
||||
// the following devices don't have init blobs:
|
||||
const char *blob = nullptr;
|
||||
uint32_t blob_size = 0;
|
||||
switch (_type[instance]) {
|
||||
#if AP_GPS_SBF_ENABLED
|
||||
case GPS_TYPE_SBF:
|
||||
@ -604,16 +606,18 @@ void AP_GPS::send_blob_start(uint8_t instance)
|
||||
#if HAL_SIM_GPS_ENABLED
|
||||
case GPS_TYPE_SITL:
|
||||
#endif // HAL_SIM_GPS_ENABLED
|
||||
send_blob_start(instance, nullptr, 0);
|
||||
return;
|
||||
// none of these GPSs have initialisation blobs
|
||||
break;
|
||||
default:
|
||||
// send combined initialisation blob, on the assumption that the
|
||||
// GPS units will parse what they need and ignore the data they
|
||||
// don't understand:
|
||||
blob = _initialisation_blob;
|
||||
blob_size = sizeof(_initialisation_blob);
|
||||
break;
|
||||
}
|
||||
|
||||
// send combined initialisation blob, on the assumption that the
|
||||
// GPS units will parse what they need and ignore the data they
|
||||
// don't understand:
|
||||
send_blob_start(instance, _initialisation_blob, sizeof(_initialisation_blob));
|
||||
send_blob_start(instance, blob, blob_size);
|
||||
}
|
||||
|
||||
/*
|
||||
|
Loading…
Reference in New Issue
Block a user