AP_GPS: remove tabs and fix coding style

This commit is contained in:
Lucas De Marchi 2017-08-22 10:30:00 -07:00
parent 44ffb67837
commit 3414883f05

View File

@ -204,48 +204,48 @@ AP_GPS_SIRF::_accumulate(uint8_t val)
/* /*
detect a SIRF GPS detect a SIRF GPS
*/ */
bool bool AP_GPS_SIRF::_detect(struct SIRF_detect_state &state, uint8_t data)
AP_GPS_SIRF::_detect(struct SIRF_detect_state &state, uint8_t data)
{ {
switch (state.step) { switch (state.step) {
case 1: case 1:
if (PREAMBLE2 == data) { if (PREAMBLE2 == data) {
state.step++; state.step++;
break; break;
} }
state.step = 0; state.step = 0;
case 0: case 0:
state.payload_length = state.payload_counter = state.checksum = 0; state.payload_length = state.payload_counter = state.checksum = 0;
if (PREAMBLE1 == data) if (PREAMBLE1 == data)
state.step++; state.step++;
break; break;
case 2: case 2:
state.step++; state.step++;
if (data != 0) { if (data != 0) {
// only look for short messages // only look for short messages
state.step = 0; state.step = 0;
} }
break; break;
case 3: case 3:
state.step++; state.step++;
state.payload_length = data; state.payload_length = data;
break; break;
case 4: case 4:
state.checksum = (state.checksum + data) & 0x7fff; state.checksum = (state.checksum + data) & 0x7fff;
if (++state.payload_counter == state.payload_length) if (++state.payload_counter == state.payload_length) {
state.step++; state.step++;
break; }
case 5: break;
state.step++; case 5:
if ((state.checksum >> 8) != data) { state.step++;
state.step = 0; if ((state.checksum >> 8) != data) {
} state.step = 0;
break; }
case 6: break;
state.step = 0; case 6:
if ((state.checksum & 0xff) == data) { state.step = 0;
return true; if ((state.checksum & 0xff) == data) {
} return true;
}
} }
return false; return false;
} }