mirror of https://github.com/ArduPilot/ardupilot
AP_GPS: added GPS_DRV_OPTIONS bit for forcing ublox GPS to 115200
this may help with some GPS modules
This commit is contained in:
parent
d1d0ab41d6
commit
1479566921
|
@ -650,6 +650,9 @@ void AP_GPS::detect_instance(uint8_t instance)
|
|||
// link to the flight controller
|
||||
static const char blob[] = UBLOX_SET_BINARY_460800;
|
||||
send_blob_start(instance, blob, sizeof(blob));
|
||||
} else 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 {
|
||||
send_blob_start(instance, _initialisation_blob, sizeof(_initialisation_blob));
|
||||
}
|
||||
|
@ -674,6 +677,7 @@ void AP_GPS::detect_instance(uint8_t instance)
|
|||
if ((_type[instance] == GPS_TYPE_AUTO ||
|
||||
_type[instance] == GPS_TYPE_UBLOX) &&
|
||||
((!_auto_config && _baudrates[dstate->current_baud] >= 38400) ||
|
||||
(_baudrates[dstate->current_baud] >= 115200 && (_driver_options & AP_GPS_Backend::DriverOptions::UBX_Use115200)) ||
|
||||
_baudrates[dstate->current_baud] == 230400) &&
|
||||
AP_GPS_UBLOX::_detect(dstate->ublox_detect_state, data)) {
|
||||
new_gps = new AP_GPS_UBLOX(*this, state[instance], _port[instance], GPS_ROLE_NORMAL);
|
||||
|
|
|
@ -85,8 +85,9 @@ public:
|
|||
}
|
||||
|
||||
enum DriverOptions : int16_t {
|
||||
UBX_MBUseUart2 = (1 << 0U),
|
||||
SBF_UseBaseForYaw = (1 << 1U),
|
||||
UBX_MBUseUart2 = (1U << 0U),
|
||||
SBF_UseBaseForYaw = (1U << 1U),
|
||||
UBX_Use115200 = (1U << 2U),
|
||||
};
|
||||
|
||||
protected:
|
||||
|
|
Loading…
Reference in New Issue