mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-22 00:28:30 -04:00
AP_GPS: do initial probe at default baudrate
this makes for much faster probe for most users
This commit is contained in:
parent
6f4ab028ca
commit
d894f7ac5d
@ -770,11 +770,15 @@ AP_GPS_Backend *AP_GPS::_detect_instance(uint8_t instance)
|
|||||||
// try the next baud rate
|
// try the next baud rate
|
||||||
// incrementing like this will skip the first element in array of bauds
|
// incrementing like this will skip the first element in array of bauds
|
||||||
// this is okay, and relied upon
|
// this is okay, and relied upon
|
||||||
dstate->current_baud++;
|
if (dstate->probe_baud == 0) {
|
||||||
if (dstate->current_baud == ARRAY_SIZE(_baudrates)) {
|
dstate->probe_baud = _port[instance]->get_baud_rate();
|
||||||
dstate->current_baud = 0;
|
} else {
|
||||||
|
dstate->current_baud++;
|
||||||
|
if (dstate->current_baud == ARRAY_SIZE(_baudrates)) {
|
||||||
|
dstate->current_baud = 0;
|
||||||
|
}
|
||||||
|
dstate->probe_baud = _baudrates[dstate->current_baud];
|
||||||
}
|
}
|
||||||
uint32_t baudrate = _baudrates[dstate->current_baud];
|
|
||||||
uint16_t rx_size=0, tx_size=0;
|
uint16_t rx_size=0, tx_size=0;
|
||||||
if (_type[instance] == GPS_TYPE_UBLOX_RTK_ROVER) {
|
if (_type[instance] == GPS_TYPE_UBLOX_RTK_ROVER) {
|
||||||
tx_size = 2048;
|
tx_size = 2048;
|
||||||
@ -782,7 +786,7 @@ AP_GPS_Backend *AP_GPS::_detect_instance(uint8_t instance)
|
|||||||
if (_type[instance] == GPS_TYPE_UBLOX_RTK_BASE) {
|
if (_type[instance] == GPS_TYPE_UBLOX_RTK_BASE) {
|
||||||
rx_size = 2048;
|
rx_size = 2048;
|
||||||
}
|
}
|
||||||
_port[instance]->begin(baudrate, rx_size, tx_size);
|
_port[instance]->begin(dstate->probe_baud, rx_size, tx_size);
|
||||||
_port[instance]->set_flow_control(AP_HAL::UARTDriver::FLOW_CONTROL_DISABLE);
|
_port[instance]->set_flow_control(AP_HAL::UARTDriver::FLOW_CONTROL_DISABLE);
|
||||||
dstate->last_baud_change_ms = now;
|
dstate->last_baud_change_ms = now;
|
||||||
|
|
||||||
|
@ -677,6 +677,7 @@ private:
|
|||||||
struct detect_state {
|
struct detect_state {
|
||||||
uint32_t last_baud_change_ms;
|
uint32_t last_baud_change_ms;
|
||||||
uint8_t current_baud;
|
uint8_t current_baud;
|
||||||
|
uint32_t probe_baud;
|
||||||
bool auto_detected_baud;
|
bool auto_detected_baud;
|
||||||
struct UBLOX_detect_state ublox_detect_state;
|
struct UBLOX_detect_state ublox_detect_state;
|
||||||
struct SIRF_detect_state sirf_detect_state;
|
struct SIRF_detect_state sirf_detect_state;
|
||||||
|
@ -139,7 +139,7 @@ void AP_GPS_Backend::_detection_message(char *buffer, const uint8_t buflen) cons
|
|||||||
"GPS %d: probing for %s at %d baud",
|
"GPS %d: probing for %s at %d baud",
|
||||||
instance + 1,
|
instance + 1,
|
||||||
name(),
|
name(),
|
||||||
int(gps._baudrates[dstate.current_baud]));
|
int(dstate.probe_baud));
|
||||||
} else {
|
} else {
|
||||||
hal.util->snprintf(buffer, buflen,
|
hal.util->snprintf(buffer, buflen,
|
||||||
"GPS %d: specified as %s",
|
"GPS %d: specified as %s",
|
||||||
|
Loading…
Reference in New Issue
Block a user