From 811550cca6ec73eb7bc1eb9a86fa21b686ad4c25 Mon Sep 17 00:00:00 2001 From: rmackay9 Date: Sun, 16 Dec 2012 16:20:33 +0900 Subject: [PATCH] AP_GPS_MTK19: small bug fix re "==" vs "=" Also saved 22 bytes of RAM by moving error message into program space. --- libraries/AP_GPS/AP_GPS_MTK19.cpp | 8 ++++---- 1 file changed, 4 insertions(+), 4 deletions(-) diff --git a/libraries/AP_GPS/AP_GPS_MTK19.cpp b/libraries/AP_GPS/AP_GPS_MTK19.cpp index a5033197d1..7e873cce55 100644 --- a/libraries/AP_GPS/AP_GPS_MTK19.cpp +++ b/libraries/AP_GPS/AP_GPS_MTK19.cpp @@ -230,12 +230,12 @@ AP_GPS_MTK19::_detect(uint8_t data) case 1: if ((mtk_type_step1 == MTK_GPS_REVISION_V16) && (PREAMBLE2_V16 == data)){ step++; - mtk_type_step2 == MTK_GPS_REVISION_V16; + mtk_type_step2 = MTK_GPS_REVISION_V16; break; } if ((mtk_type_step1 == MTK_GPS_REVISION_V19) && (PREAMBLE2_V19 == data)){ step++; - mtk_type_step2 == MTK_GPS_REVISION_V19; + mtk_type_step2 = MTK_GPS_REVISION_V19; break; } mtk_type_step1 = 0; @@ -257,7 +257,7 @@ AP_GPS_MTK19::_detect(uint8_t data) case 4: step++; if (ck_a != data) { - Serial.printf("wrong ck_a\n"); + Serial.print_P(PSTR("wrong ck_a\n")); step = 0; } break; @@ -266,7 +266,7 @@ AP_GPS_MTK19::_detect(uint8_t data) if (ck_b == data) { return true; } - Serial.printf("wrong ck_b\n"); + Serial.print_P(PSTR("wrong ck_b\n")); break; } return false;