mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-02 05:58:30 -04:00
AP_GPS: force flow control off on GPS serial ports
This commit is contained in:
parent
5980ff8e1c
commit
362b53e1da
@ -183,6 +183,7 @@ AP_GPS::detect_instance(uint8_t instance)
|
||||
}
|
||||
uint32_t baudrate = pgm_read_dword(&_baudrates[dstate->last_baud]);
|
||||
_port[instance]->begin(baudrate);
|
||||
_port[instance]->set_flow_control(AP_HAL::UARTDriver::FLOW_CONTROL_DISABLE);
|
||||
dstate->last_baud_change_ms = now;
|
||||
send_blob_start(instance, _initialisation_blob, sizeof(_initialisation_blob));
|
||||
}
|
||||
|
Loading…
Reference in New Issue
Block a user