From 3414883f052132ead3dc35d73de8b6808155762a Mon Sep 17 00:00:00 2001 From: Lucas De Marchi Date: Tue, 22 Aug 2017 10:30:00 -0700 Subject: [PATCH] AP_GPS: remove tabs and fix coding style --- libraries/AP_GPS/AP_GPS_SIRF.cpp | 82 ++++++++++++++++---------------- 1 file changed, 41 insertions(+), 41 deletions(-) diff --git a/libraries/AP_GPS/AP_GPS_SIRF.cpp b/libraries/AP_GPS/AP_GPS_SIRF.cpp index 86893fde13..68d64bee0a 100644 --- a/libraries/AP_GPS/AP_GPS_SIRF.cpp +++ b/libraries/AP_GPS/AP_GPS_SIRF.cpp @@ -204,48 +204,48 @@ AP_GPS_SIRF::_accumulate(uint8_t val) /* detect a SIRF GPS */ -bool -AP_GPS_SIRF::_detect(struct SIRF_detect_state &state, uint8_t data) +bool AP_GPS_SIRF::_detect(struct SIRF_detect_state &state, uint8_t data) { - switch (state.step) { - case 1: - if (PREAMBLE2 == data) { - state.step++; - break; - } - state.step = 0; - case 0: - state.payload_length = state.payload_counter = state.checksum = 0; - if (PREAMBLE1 == data) - state.step++; - break; - case 2: - state.step++; - if (data != 0) { - // only look for short messages - state.step = 0; - } - break; - case 3: - state.step++; - state.payload_length = data; - break; - case 4: - state.checksum = (state.checksum + data) & 0x7fff; - if (++state.payload_counter == state.payload_length) - state.step++; - break; - case 5: - state.step++; - if ((state.checksum >> 8) != data) { - state.step = 0; - } - break; - case 6: - state.step = 0; - if ((state.checksum & 0xff) == data) { - return true; - } + switch (state.step) { + case 1: + if (PREAMBLE2 == data) { + state.step++; + break; + } + state.step = 0; + case 0: + state.payload_length = state.payload_counter = state.checksum = 0; + if (PREAMBLE1 == data) + state.step++; + break; + case 2: + state.step++; + if (data != 0) { + // only look for short messages + state.step = 0; + } + break; + case 3: + state.step++; + state.payload_length = data; + break; + case 4: + state.checksum = (state.checksum + data) & 0x7fff; + if (++state.payload_counter == state.payload_length) { + state.step++; + } + break; + case 5: + state.step++; + if ((state.checksum >> 8) != data) { + state.step = 0; + } + break; + case 6: + state.step = 0; + if ((state.checksum & 0xff) == data) { + return true; + } } return false; }