AP_GPS: Fix incorrect incrementing of last_baud rate

This is a revert of 7c3b8dceb which tried to start at index 0 of the
array of baudrates, however because of the way last_baud is used
this lead to a GPS always being reported as being 1 index off which
lead to users getting reports of baud rates that their GPS wasn't
configured for

Also renames last_baud to be current_baud as that is how it's
actuallly used and should reduce future confusion

And fixed some tabs/vs space issues around where the last_baud rate
was incremented.
This commit is contained in:
Michael du Breuil 2016-09-23 23:16:40 -07:00 committed by Tom Pittenger
parent 7091daa1cf
commit 9c4b3ec1e1
2 changed files with 23 additions and 21 deletions

View File

@ -258,11 +258,13 @@ AP_GPS::detect_instance(uint8_t instance)
if (now - dstate->last_baud_change_ms > GPS_BAUD_TIME_MS) {
// try the next baud rate
if (dstate->last_baud == ARRAY_SIZE(_baudrates)) {
dstate->last_baud = 0;
// incrementing like this will skip the first element in array of bauds
// this is okay, and relied upon
dstate->current_baud++;
if (dstate->current_baud == ARRAY_SIZE(_baudrates)) {
dstate->current_baud = 0;
}
uint32_t baudrate = _baudrates[dstate->last_baud];
dstate->last_baud++;
uint32_t baudrate = _baudrates[dstate->current_baud];
_port[instance]->begin(baudrate);
_port[instance]->set_flow_control(AP_HAL::UARTDriver::FLOW_CONTROL_DISABLE);
dstate->last_baud_change_ms = now;
@ -291,41 +293,41 @@ AP_GPS::detect_instance(uint8_t instance)
for.
*/
if ((_type[instance] == GPS_TYPE_AUTO || _type[instance] == GPS_TYPE_UBLOX) &&
_baudrates[dstate->last_baud] >= 38400 &&
_baudrates[dstate->current_baud] >= 38400 &&
AP_GPS_UBLOX::_detect(dstate->ublox_detect_state, data)) {
_broadcast_gps_type("u-blox", instance, dstate->last_baud);
_broadcast_gps_type("u-blox", instance, dstate->current_baud);
new_gps = new AP_GPS_UBLOX(*this, state[instance], _port[instance]);
}
else if ((_type[instance] == GPS_TYPE_AUTO || _type[instance] == GPS_TYPE_MTK19) &&
AP_GPS_MTK19::_detect(dstate->mtk19_detect_state, data)) {
_broadcast_gps_type("MTK19", instance, dstate->last_baud);
_broadcast_gps_type("MTK19", instance, dstate->current_baud);
new_gps = new AP_GPS_MTK19(*this, state[instance], _port[instance]);
}
else if ((_type[instance] == GPS_TYPE_AUTO || _type[instance] == GPS_TYPE_MTK) &&
AP_GPS_MTK::_detect(dstate->mtk_detect_state, data)) {
_broadcast_gps_type("MTK", instance, dstate->last_baud);
_broadcast_gps_type("MTK", instance, dstate->current_baud);
new_gps = new AP_GPS_MTK(*this, state[instance], _port[instance]);
}
else if ((_type[instance] == GPS_TYPE_AUTO || _type[instance] == GPS_TYPE_SBP) &&
AP_GPS_SBP::_detect(dstate->sbp_detect_state, data)) {
_broadcast_gps_type("SBP", instance, dstate->last_baud);
_broadcast_gps_type("SBP", instance, dstate->current_baud);
new_gps = new AP_GPS_SBP(*this, state[instance], _port[instance]);
}
// save a bit of code space on a 1280
else if ((_type[instance] == GPS_TYPE_AUTO || _type[instance] == GPS_TYPE_SIRF) &&
AP_GPS_SIRF::_detect(dstate->sirf_detect_state, data)) {
_broadcast_gps_type("SIRF", instance, dstate->last_baud);
_broadcast_gps_type("SIRF", instance, dstate->current_baud);
new_gps = new AP_GPS_SIRF(*this, state[instance], _port[instance]);
}
else if ((_type[instance] == GPS_TYPE_AUTO || _type[instance] == GPS_TYPE_ERB) &&
AP_GPS_ERB::_detect(dstate->erb_detect_state, data)) {
_broadcast_gps_type("ERB", instance, dstate->last_baud);
_broadcast_gps_type("ERB", instance, dstate->current_baud);
new_gps = new AP_GPS_ERB(*this, state[instance], _port[instance]);
}
// user has to explicitly set the MAV type, do not use AUTO
// Do not try to detect the MAV type, assume it's there
else if (_type[instance] == GPS_TYPE_MAV) {
_broadcast_gps_type("MAV", instance, dstate->last_baud);
_broadcast_gps_type("MAV", instance, dstate->current_baud);
new_gps = new AP_GPS_MAV(*this, state[instance], NULL);
}
else if (now - dstate->detect_started_ms > (ARRAY_SIZE(_baudrates) * GPS_BAUD_TIME_MS)) {
@ -333,7 +335,7 @@ AP_GPS::detect_instance(uint8_t instance)
// a MTK or UBLOX which has booted in NMEA mode
if ((_type[instance] == GPS_TYPE_AUTO || _type[instance] == GPS_TYPE_NMEA) &&
AP_GPS_NMEA::_detect(dstate->nmea_detect_state, data)) {
_broadcast_gps_type("NMEA", instance, dstate->last_baud);
_broadcast_gps_type("NMEA", instance, dstate->current_baud);
new_gps = new AP_GPS_NMEA(*this, state[instance], _port[instance]);
}
}

View File

@ -389,7 +389,7 @@ private:
struct detect_state {
uint32_t detect_started_ms;
uint32_t last_baud_change_ms;
uint8_t last_baud;
uint8_t current_baud;
struct UBLOX_detect_state ublox_detect_state;
struct MTK_detect_state mtk_detect_state;
struct MTK19_detect_state mtk19_detect_state;