diff --git a/libraries/AP_GPS/AP_GPS_MTK.cpp b/libraries/AP_GPS/AP_GPS_MTK.cpp index b571f9f5dd..e48f8a518e 100644 --- a/libraries/AP_GPS/AP_GPS_MTK.cpp +++ b/libraries/AP_GPS/AP_GPS_MTK.cpp @@ -1,12 +1,12 @@ /* AP_GPS_MTK.cpp - Ublox GPS library for Arduino Code by Jordi MuÃ’oz and Jose Julio. DIYDrones.com - This code works with boards based on ATMega168/328 and ATMega1280 (Serial port 1) + This code works with boards based on ATMega168 / 328 and ATMega1280 (Serial port 1) - This library is free software; you can redistribute it and/or - modify it under the terms of the GNU Lesser General Public - License as published by the Free Software Foundation; either - version 2.1 of the License, or (at your option) any later version. + This library is free software; you can redistribute it and / or + modify it under the terms of the GNU Lesser General Public + License as published by the Free Software Foundation; either + version 2.1 of the License, or (at your option) any later version. GPS configuration : Costum protocol Baud rate : 38400 @@ -26,8 +26,8 @@ fix : 1: GPS NO fix, 2: 2D fix, 3: 3D fix. */ -#include "AP_GPS_MTK.h" +#include "AP_GPS_MTK.h" // Constructors //////////////////////////////////////////////////////////////// AP_GPS_MTK::AP_GPS_MTK() @@ -38,12 +38,13 @@ AP_GPS_MTK::AP_GPS_MTK() // Public Methods ////////////////////////////////////////////////////////////// void AP_GPS_MTK::init(void) { - new_data = 0; - ck_a = 0; - ck_b = 0; - step = 0; - fix = 0; + ck_a = 0; + ck_b = 0; + step = 0; + new_data = 0; + fix = 0; print_errors = 0; + // initialize serial port #if defined(__AVR_ATmega1280__) Serial1.begin(38400); // Serial port 1 on ATMega1280 @@ -66,7 +67,7 @@ void AP_GPS_MTK::update(void) numc = Serial.available(); #endif if (numc > 0) - for (int i=0;i 0){ - Serial.println(" "); for (int i = 0;i < numc;i++){ // Process bytes received #if defined(__AVR_ATmega1280__) data = Serial1.read(); #else data = Serial.read(); #endif - Serial.print(data,HEX); - Serial.println(","); - switch(step){ // Normally we start from zero. This is a state machine - case 0: - if(data == 0xB5) // UBX sync char 1 - step++; // OH first data packet is correct, so jump to the next step + + switch(step){ + case 0: + if(data == 0xB5) + step++; break; case 1: - if(data == 0x62) // UBX sync char 2 - step++; // ooh! The second data packet is correct, jump to the step 2 + if(data == 0x62) + step++; else - step = 0; // Nop, is not correct so restart to step zero and try again. + step = 0; break; case 2: @@ -166,26 +160,25 @@ void AP_GPS_UBLOX::update(void) } // Private Methods ////////////////////////////////////////////////////////////// -void AP_GPS_UBLOX::parse_gps(void) +void +AP_GPS_UBLOX::parse_gps(void) { int j; //Verifing if we are in msg_class 1, you can change this "IF" for a "Switch" in case you want to use other UBX classes.. // In this case all the message im using are in msg_class 1, to know more about classes check PAGE 60 of DataSheet. - if(msg_class == 0x01) - { - switch(id) //Checking the UBX ID - { + if(msg_class == 0x01){ + switch(id) {//Checking the UBX ID case 0x02: // ID NAV - POSLLH j = 0; time = join_4_bytes(&buffer[j]); // ms Time of week j += 4; - longitude = join_4_bytes(&buffer[j]); // lon * 10000000 + longitude = join_4_bytes(&buffer[j]); // lon * 10,000,000 j += 4; - lattitude = join_4_bytes(&buffer[j]); // lat * 10000000 + lattitude = join_4_bytes(&buffer[j]); // lat * 10,000,000 j += 4; //altitude = join_4_bytes(&buffer[j]); // elipsoid heigth mm j += 4; - altitude = (float)join_4_bytes(&buffer[j]); // MSL heigth mm + altitude = (float)join_4_bytes(&buffer[j]) / 10; // MSL heigth mm //j+=4; /* hacc = (float)join_4_bytes(&buffer[j]) / (float)1000; @@ -198,7 +191,7 @@ void AP_GPS_UBLOX::parse_gps(void) case 0x03: //ID NAV - STATUS //if(buffer[4] >= 0x03) - if((buffer[4] >= 0x03) && (buffer[5] & 0x01)) + if((buffer[4] >= 0x03) && (buffer[5] & 0x01)) fix = 1; // valid position else fix = 0; // invalid position @@ -223,8 +216,8 @@ void AP_GPS_UBLOX::parse_gps(void) ground_course /= 1000; // Rescale heading to deg * 100 j += 4; break; - } - } + } + } } // Join 4 bytes into a long diff --git a/libraries/AP_GPS/examples/GPS_MTK_test/GPS_MTK_test.pde b/libraries/AP_GPS/examples/GPS_MTK_test/GPS_MTK_test.pde index 04b5e23714..40d1b5886b 100644 --- a/libraries/AP_GPS/examples/GPS_MTK_test/GPS_MTK_test.pde +++ b/libraries/AP_GPS/examples/GPS_MTK_test/GPS_MTK_test.pde @@ -10,6 +10,7 @@ AP_GPS_MTK gps; #define T6 1000000 +#define T7 10000000 void setup() { diff --git a/libraries/AP_GPS/examples/GPS_NMEA_test/GPS_NMEA_test.pde b/libraries/AP_GPS/examples/GPS_NMEA_test/GPS_NMEA_test.pde index 8ac8982097..8720011db4 100644 --- a/libraries/AP_GPS/examples/GPS_NMEA_test/GPS_NMEA_test.pde +++ b/libraries/AP_GPS/examples/GPS_NMEA_test/GPS_NMEA_test.pde @@ -10,7 +10,7 @@ AP_GPS_NMEA gps; #define T6 1000000 -#define T7 1000000 +#define T7 10000000 void setup() { diff --git a/libraries/AP_GPS/examples/GPS_UBLOX_test/GPS_UBLOX_test.pde b/libraries/AP_GPS/examples/GPS_UBLOX_test/GPS_UBLOX_test.pde index db60075ec1..f90ecbb860 100644 --- a/libraries/AP_GPS/examples/GPS_UBLOX_test/GPS_UBLOX_test.pde +++ b/libraries/AP_GPS/examples/GPS_UBLOX_test/GPS_UBLOX_test.pde @@ -10,7 +10,7 @@ AP_GPS_UBLOX gps; #define T6 1000000 -#define T7 1000000 +#define T7 10000000 void setup() {