mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 14:38:30 -04:00
updates - Ublox now working
git-svn-id: https://arducopter.googlecode.com/svn/trunk@313 f9c3cf11-9bcb-44bc-f272-b75c42450872
This commit is contained in:
parent
d681c067a1
commit
241b710001
@ -1,9 +1,9 @@
|
|||||||
/*
|
/*
|
||||||
AP_GPS_MTK.cpp - Ublox GPS library for Arduino
|
AP_GPS_MTK.cpp - Ublox GPS library for Arduino
|
||||||
Code by Jordi MuÒoz and Jose Julio. DIYDrones.com
|
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
|
This library is free software; you can redistribute it and / or
|
||||||
modify it under the terms of the GNU Lesser General Public
|
modify it under the terms of the GNU Lesser General Public
|
||||||
License as published by the Free Software Foundation; either
|
License as published by the Free Software Foundation; either
|
||||||
version 2.1 of the License, or (at your option) any later version.
|
version 2.1 of the License, or (at your option) any later version.
|
||||||
@ -26,8 +26,8 @@
|
|||||||
fix : 1: GPS NO fix, 2: 2D fix, 3: 3D fix.
|
fix : 1: GPS NO fix, 2: 2D fix, 3: 3D fix.
|
||||||
|
|
||||||
*/
|
*/
|
||||||
#include "AP_GPS_MTK.h"
|
|
||||||
|
|
||||||
|
#include "AP_GPS_MTK.h"
|
||||||
|
|
||||||
// Constructors ////////////////////////////////////////////////////////////////
|
// Constructors ////////////////////////////////////////////////////////////////
|
||||||
AP_GPS_MTK::AP_GPS_MTK()
|
AP_GPS_MTK::AP_GPS_MTK()
|
||||||
@ -38,12 +38,13 @@ AP_GPS_MTK::AP_GPS_MTK()
|
|||||||
// Public Methods //////////////////////////////////////////////////////////////
|
// Public Methods //////////////////////////////////////////////////////////////
|
||||||
void AP_GPS_MTK::init(void)
|
void AP_GPS_MTK::init(void)
|
||||||
{
|
{
|
||||||
new_data = 0;
|
|
||||||
ck_a = 0;
|
ck_a = 0;
|
||||||
ck_b = 0;
|
ck_b = 0;
|
||||||
step = 0;
|
step = 0;
|
||||||
|
new_data = 0;
|
||||||
fix = 0;
|
fix = 0;
|
||||||
print_errors = 0;
|
print_errors = 0;
|
||||||
|
|
||||||
// initialize serial port
|
// initialize serial port
|
||||||
#if defined(__AVR_ATmega1280__)
|
#if defined(__AVR_ATmega1280__)
|
||||||
Serial1.begin(38400); // Serial port 1 on ATMega1280
|
Serial1.begin(38400); // Serial port 1 on ATMega1280
|
||||||
@ -66,7 +67,7 @@ void AP_GPS_MTK::update(void)
|
|||||||
numc = Serial.available();
|
numc = Serial.available();
|
||||||
#endif
|
#endif
|
||||||
if (numc > 0)
|
if (numc > 0)
|
||||||
for (int i=0;i<numc;i++){ // Process bytes received
|
for (int i = 0; i < numc; i++){ // Process bytes received
|
||||||
#if defined(__AVR_ATmega1280__)
|
#if defined(__AVR_ATmega1280__)
|
||||||
data = Serial1.read();
|
data = Serial1.read();
|
||||||
#else
|
#else
|
||||||
@ -75,15 +76,15 @@ void AP_GPS_MTK::update(void)
|
|||||||
|
|
||||||
switch(step){
|
switch(step){
|
||||||
case 0:
|
case 0:
|
||||||
if(data==0xB5) // UBX sync char 1
|
if(data == 0xB5)
|
||||||
step++; //OH first data packet is correct, so jump to the next step
|
step++;
|
||||||
break;
|
break;
|
||||||
|
|
||||||
case 1:
|
case 1:
|
||||||
if(data==0x62) // UBX sync char 2
|
if(data == 0x62)
|
||||||
step++; //ooh! The second data packet is correct, jump to the step 2
|
step++;
|
||||||
else
|
else
|
||||||
step=0; //Nop, is not correct so restart to step zero and try again.
|
step = 0;
|
||||||
break;
|
break;
|
||||||
|
|
||||||
case 2:
|
case 2:
|
||||||
@ -128,8 +129,8 @@ void AP_GPS_MTK::update(void)
|
|||||||
ck_a = 0;
|
ck_a = 0;
|
||||||
ck_b = 0;
|
ck_b = 0;
|
||||||
break;
|
break;
|
||||||
}// End switch
|
} // End switch
|
||||||
}// End for
|
} // End for
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
||||||
@ -143,11 +144,11 @@ AP_GPS_MTK::parse_gps(void)
|
|||||||
if(msg_class == 0x01) {
|
if(msg_class == 0x01) {
|
||||||
switch(id){
|
switch(id){
|
||||||
//Checking the UBX ID
|
//Checking the UBX ID
|
||||||
case 0x05: //ID Custom
|
case 0x05: // ID Custom
|
||||||
j = 0;
|
j = 0;
|
||||||
lattitude= join_4_bytes(&buffer[j]); // lon*10000000
|
lattitude= join_4_bytes(&buffer[j]); // lon * 10000000
|
||||||
j += 4;
|
j += 4;
|
||||||
longitude = join_4_bytes(&buffer[j]); // lat*10000000
|
longitude = join_4_bytes(&buffer[j]); // lat * 10000000
|
||||||
j += 4;
|
j += 4;
|
||||||
altitude = join_4_bytes(&buffer[j]); // MSL
|
altitude = join_4_bytes(&buffer[j]); // MSL
|
||||||
j += 4;
|
j += 4;
|
||||||
|
@ -1,7 +1,7 @@
|
|||||||
/*
|
/*
|
||||||
AP_GPS_UBLOX.cpp - Ublox GPS library for Arduino
|
AP_GPS_UBLOX.cpp - Ublox GPS library for Arduino
|
||||||
Code by Jordi Muñoz and Jose Julio. DIYDrones.com
|
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
|
This library is free software; you can redistribute it and / or
|
||||||
modify it under the terms of the GNU Lesser General Public
|
modify it under the terms of the GNU Lesser General Public
|
||||||
@ -25,8 +25,8 @@
|
|||||||
Lattitude : Lattitude * 10000000 (long value)
|
Lattitude : Lattitude * 10000000 (long value)
|
||||||
Longitude : Longitude * 10000000 (long value)
|
Longitude : Longitude * 10000000 (long value)
|
||||||
altitude : altitude * 100 (meters) (long value)
|
altitude : altitude * 100 (meters) (long value)
|
||||||
Ground_speed : Speed (m / s) * 100 (long value)
|
ground_speed : Speed (m/s) * 100 (long value)
|
||||||
Ground_course : Course (degrees) * 100 (long value)
|
ground_course : Course (degrees) * 100 (long value)
|
||||||
new_data : 1 when a new data is received.
|
new_data : 1 when a new data is received.
|
||||||
You need to write a 0 to new_data when you read the data
|
You need to write a 0 to new_data when you read the data
|
||||||
fix : 1: GPS FIX, 0: No fix (normal logic)
|
fix : 1: GPS FIX, 0: No fix (normal logic)
|
||||||
@ -35,14 +35,13 @@
|
|||||||
|
|
||||||
#include "AP_GPS_UBLOX.h"
|
#include "AP_GPS_UBLOX.h"
|
||||||
|
|
||||||
// Constructors // /// /// /// /// /// /// /// /// /// /// /// /// /// /// /// /// /// /// /// /// //
|
// Constructors ////////////////////////////////////////////////////////////////
|
||||||
AP_GPS_UBLOX::AP_GPS_UBLOX()
|
AP_GPS_UBLOX::AP_GPS_UBLOX()
|
||||||
{
|
{
|
||||||
print_errors = 1;
|
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
||||||
// Public Methods // /// /// /// /// /// /// /// /// /// /// /// /// /// /// /// /// /// /// /// ///
|
// Public Methods ////////////////////////////////////////////////////////////////////
|
||||||
void AP_GPS_UBLOX::init(void)
|
void AP_GPS_UBLOX::init(void)
|
||||||
{
|
{
|
||||||
ck_a = 0;
|
ck_a = 0;
|
||||||
@ -52,7 +51,6 @@ void AP_GPS_UBLOX::init(void)
|
|||||||
fix = 0;
|
fix = 0;
|
||||||
print_errors = 0;
|
print_errors = 0;
|
||||||
|
|
||||||
|
|
||||||
// initialize serial port
|
// initialize serial port
|
||||||
#if defined(__AVR_ATmega1280__)
|
#if defined(__AVR_ATmega1280__)
|
||||||
Serial1.begin(38400); // Serial port 1 on ATMega1280
|
Serial1.begin(38400); // Serial port 1 on ATMega1280
|
||||||
@ -74,30 +72,26 @@ void AP_GPS_UBLOX::update(void)
|
|||||||
#else
|
#else
|
||||||
numc = Serial.available();
|
numc = Serial.available();
|
||||||
#endif
|
#endif
|
||||||
Serial.print("numc ");
|
|
||||||
Serial.println(numc,DEC);
|
|
||||||
|
|
||||||
if (numc > 0){
|
if (numc > 0){
|
||||||
Serial.println(" ");
|
|
||||||
for (int i = 0;i < numc;i++){ // Process bytes received
|
for (int i = 0;i < numc;i++){ // Process bytes received
|
||||||
#if defined(__AVR_ATmega1280__)
|
#if defined(__AVR_ATmega1280__)
|
||||||
data = Serial1.read();
|
data = Serial1.read();
|
||||||
#else
|
#else
|
||||||
data = Serial.read();
|
data = Serial.read();
|
||||||
#endif
|
#endif
|
||||||
Serial.print(data,HEX);
|
|
||||||
Serial.println(",");
|
switch(step){
|
||||||
switch(step){ // Normally we start from zero. This is a state machine
|
|
||||||
case 0:
|
case 0:
|
||||||
if(data == 0xB5) // UBX sync char 1
|
if(data == 0xB5)
|
||||||
step++; // OH first data packet is correct, so jump to the next step
|
step++;
|
||||||
break;
|
break;
|
||||||
|
|
||||||
case 1:
|
case 1:
|
||||||
if(data == 0x62) // UBX sync char 2
|
if(data == 0x62)
|
||||||
step++; // ooh! The second data packet is correct, jump to the step 2
|
step++;
|
||||||
else
|
else
|
||||||
step = 0; // Nop, is not correct so restart to step zero and try again.
|
step = 0;
|
||||||
break;
|
break;
|
||||||
|
|
||||||
case 2:
|
case 2:
|
||||||
@ -166,26 +160,25 @@ void AP_GPS_UBLOX::update(void)
|
|||||||
}
|
}
|
||||||
|
|
||||||
// Private Methods //////////////////////////////////////////////////////////////
|
// Private Methods //////////////////////////////////////////////////////////////
|
||||||
void AP_GPS_UBLOX::parse_gps(void)
|
void
|
||||||
|
AP_GPS_UBLOX::parse_gps(void)
|
||||||
{
|
{
|
||||||
int j;
|
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..
|
//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.
|
// 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)
|
if(msg_class == 0x01){
|
||||||
{
|
switch(id) {//Checking the UBX ID
|
||||||
switch(id) //Checking the UBX ID
|
|
||||||
{
|
|
||||||
case 0x02: // ID NAV - POSLLH
|
case 0x02: // ID NAV - POSLLH
|
||||||
j = 0;
|
j = 0;
|
||||||
time = join_4_bytes(&buffer[j]); // ms Time of week
|
time = join_4_bytes(&buffer[j]); // ms Time of week
|
||||||
j += 4;
|
j += 4;
|
||||||
longitude = join_4_bytes(&buffer[j]); // lon * 10000000
|
longitude = join_4_bytes(&buffer[j]); // lon * 10,000,000
|
||||||
j += 4;
|
j += 4;
|
||||||
lattitude = join_4_bytes(&buffer[j]); // lat * 10000000
|
lattitude = join_4_bytes(&buffer[j]); // lat * 10,000,000
|
||||||
j += 4;
|
j += 4;
|
||||||
//altitude = join_4_bytes(&buffer[j]); // elipsoid heigth mm
|
//altitude = join_4_bytes(&buffer[j]); // elipsoid heigth mm
|
||||||
j += 4;
|
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;
|
//j+=4;
|
||||||
/*
|
/*
|
||||||
hacc = (float)join_4_bytes(&buffer[j]) / (float)1000;
|
hacc = (float)join_4_bytes(&buffer[j]) / (float)1000;
|
||||||
|
@ -10,6 +10,7 @@
|
|||||||
|
|
||||||
AP_GPS_MTK gps;
|
AP_GPS_MTK gps;
|
||||||
#define T6 1000000
|
#define T6 1000000
|
||||||
|
#define T7 10000000
|
||||||
|
|
||||||
void setup()
|
void setup()
|
||||||
{
|
{
|
||||||
|
@ -10,7 +10,7 @@
|
|||||||
|
|
||||||
AP_GPS_NMEA gps;
|
AP_GPS_NMEA gps;
|
||||||
#define T6 1000000
|
#define T6 1000000
|
||||||
#define T7 1000000
|
#define T7 10000000
|
||||||
|
|
||||||
void setup()
|
void setup()
|
||||||
{
|
{
|
||||||
|
@ -10,7 +10,7 @@
|
|||||||
|
|
||||||
AP_GPS_UBLOX gps;
|
AP_GPS_UBLOX gps;
|
||||||
#define T6 1000000
|
#define T6 1000000
|
||||||
#define T7 1000000
|
#define T7 10000000
|
||||||
|
|
||||||
void setup()
|
void setup()
|
||||||
{
|
{
|
||||||
|
Loading…
Reference in New Issue
Block a user