mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
AP_GPS: Don't send SBF config unless there is free space in the port
This commit is contained in:
parent
c0da87c066
commit
4c4e613f6a
@ -91,10 +91,13 @@ AP_GPS_SBF::read(void)
|
|||||||
uint32_t now = AP_HAL::millis();
|
uint32_t now = AP_HAL::millis();
|
||||||
if (now > _init_blob_time) {
|
if (now > _init_blob_time) {
|
||||||
if (now > _config_last_ack_time + 2000) {
|
if (now > _config_last_ack_time + 2000) {
|
||||||
// try to enable input on the GPS port if we have not made progress on configuring it
|
const size_t port_enable_len = strlen(_port_enable);
|
||||||
Debug("SBF Sending port enable");
|
if (port_enable_len <= port->txspace()) {
|
||||||
port->write((const uint8_t*)_port_enable, strlen(_port_enable));
|
// try to enable input on the GPS port if we have not made progress on configuring it
|
||||||
_config_last_ack_time = now;
|
Debug("SBF Sending port enable");
|
||||||
|
port->write((const uint8_t*)_port_enable, port_enable_len);
|
||||||
|
_config_last_ack_time = now;
|
||||||
|
}
|
||||||
} else if (readyForCommand) {
|
} else if (readyForCommand) {
|
||||||
if (config_string == nullptr) {
|
if (config_string == nullptr) {
|
||||||
switch (config_step) {
|
switch (config_step) {
|
||||||
@ -126,9 +129,12 @@ AP_GPS_SBF::read(void)
|
|||||||
}
|
}
|
||||||
|
|
||||||
if (config_string != nullptr) {
|
if (config_string != nullptr) {
|
||||||
Debug("SBF sending init string: %s", config_string);
|
const size_t config_length = strlen(config_string);
|
||||||
port->write((const uint8_t*)config_string, strlen(config_string));
|
if (config_length <= port->txspace()) {
|
||||||
readyForCommand = false;
|
Debug("SBF sending init string: %s", config_string);
|
||||||
|
port->write((const uint8_t*)config_string, config_length);
|
||||||
|
readyForCommand = false;
|
||||||
|
}
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
Loading…
Reference in New Issue
Block a user