mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-21 23:33:57 -04:00
AP_GPS: tidy initialisation of sending blobs
This commit is contained in:
parent
4b6590734a
commit
aa72559d00
@ -554,14 +554,19 @@ void AP_GPS::send_blob_start(uint8_t instance, const char *_blob, uint16_t size)
|
||||
}
|
||||
|
||||
/*
|
||||
initialise state for sending binary blob initialisation strings
|
||||
initialise state for sending binary blob initialisation strings. We
|
||||
may choose different blobs not just based on type but also based on
|
||||
parameters.
|
||||
*/
|
||||
void AP_GPS::send_blob_start(uint8_t instance)
|
||||
{
|
||||
if (_type[instance] == GPS_TYPE_UBLOX && (_driver_options & AP_GPS_Backend::DriverOptions::UBX_Use115200)) {
|
||||
static const char blob[] = UBLOX_SET_BINARY_115200;
|
||||
send_blob_start(instance, blob, sizeof(blob));
|
||||
} else if ((_type[instance] == GPS_TYPE_UBLOX_RTK_BASE ||
|
||||
return;
|
||||
}
|
||||
|
||||
if ((_type[instance] == GPS_TYPE_UBLOX_RTK_BASE ||
|
||||
_type[instance] == GPS_TYPE_UBLOX_RTK_ROVER) &&
|
||||
((_driver_options.get() & AP_GPS_Backend::DriverOptions::UBX_MBUseUart2) == 0)) {
|
||||
// we use 460800 when doing moving baseline as we need
|
||||
@ -570,13 +575,17 @@ void AP_GPS::send_blob_start(uint8_t instance)
|
||||
// link to the flight controller
|
||||
static const char blob[] = UBLOX_SET_BINARY_460800;
|
||||
send_blob_start(instance, blob, sizeof(blob));
|
||||
#if AP_GPS_NMEA_ENABLED
|
||||
} else if (_type[instance] == GPS_TYPE_HEMI) {
|
||||
send_blob_start(instance, AP_GPS_NMEA_HEMISPHERE_INIT_STRING, strlen(AP_GPS_NMEA_HEMISPHERE_INIT_STRING));
|
||||
#endif // AP_GPS_NMEA_ENABLED
|
||||
} else {
|
||||
send_blob_start(instance, _initialisation_blob, sizeof(_initialisation_blob));
|
||||
return;
|
||||
}
|
||||
|
||||
#if AP_GPS_NMEA_ENABLED
|
||||
if (_type[instance] == GPS_TYPE_HEMI) {
|
||||
send_blob_start(instance, AP_GPS_NMEA_HEMISPHERE_INIT_STRING, strlen(AP_GPS_NMEA_HEMISPHERE_INIT_STRING));
|
||||
return;
|
||||
}
|
||||
#endif // AP_GPS_NMEA_ENABLED
|
||||
|
||||
send_blob_start(instance, _initialisation_blob, sizeof(_initialisation_blob));
|
||||
}
|
||||
|
||||
/*
|
||||
|
Loading…
Reference in New Issue
Block a user