mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
AP_GPS: ensure uart buffer sizes are OK for RTK
rover needs higher tx size, base needs higher rx size
This commit is contained in:
parent
64869b6e16
commit
848e1bfdf8
@ -763,7 +763,14 @@ AP_GPS_Backend *AP_GPS::_detect_instance(uint8_t instance)
|
||||
dstate->current_baud = 0;
|
||||
}
|
||||
uint32_t baudrate = _baudrates[dstate->current_baud];
|
||||
_port[instance]->begin(baudrate);
|
||||
uint16_t rx_size=0, tx_size=0;
|
||||
if (_type[instance] == GPS_TYPE_UBLOX_RTK_ROVER) {
|
||||
tx_size = 2048;
|
||||
}
|
||||
if (_type[instance] == GPS_TYPE_UBLOX_RTK_BASE) {
|
||||
rx_size = 2048;
|
||||
}
|
||||
_port[instance]->begin(baudrate, rx_size, tx_size);
|
||||
_port[instance]->set_flow_control(AP_HAL::UARTDriver::FLOW_CONTROL_DISABLE);
|
||||
dstate->last_baud_change_ms = now;
|
||||
|
||||
|
Loading…
Reference in New Issue
Block a user