mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-22 00:28:30 -04:00
AP_GPS: Fixed GPS serial speeds starting at 1 instead of 0
The counting of this will increment the counter before selecting the baud speed, skipping the first baud rate.
This commit is contained in:
parent
3dd4f30460
commit
7c3b8dceb9
@ -254,11 +254,11 @@ AP_GPS::detect_instance(uint8_t instance)
|
||||
|
||||
if (now - dstate->last_baud_change_ms > GPS_BAUD_TIME_MS) {
|
||||
// try the next baud rate
|
||||
dstate->last_baud++;
|
||||
if (dstate->last_baud == ARRAY_SIZE(_baudrates)) {
|
||||
dstate->last_baud = 0;
|
||||
}
|
||||
uint32_t baudrate = _baudrates[dstate->last_baud];
|
||||
dstate->last_baud++;
|
||||
_port[instance]->begin(baudrate);
|
||||
_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