mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
New GPS Lib
git-svn-id: https://arducopter.googlecode.com/svn/trunk@342 f9c3cf11-9bcb-44bc-f272-b75c42450872
This commit is contained in:
parent
4625fb64b6
commit
4f02edac51
@ -27,6 +27,7 @@
|
||||
|
||||
*/
|
||||
#include "AP_GPS_IMU.h"
|
||||
#include "WProgram.h"
|
||||
|
||||
|
||||
// Constructors ////////////////////////////////////////////////////////////////
|
||||
|
@ -1,10 +1,10 @@
|
||||
#ifndef AP_GPS_IMU_h
|
||||
#define AP_GPS_IMU_h
|
||||
|
||||
#include "AP_GPS.h"
|
||||
#include <GPS.h>
|
||||
#define MAXPAYLOAD 32
|
||||
|
||||
class AP_GPS_IMU : public AP_GPS
|
||||
class AP_GPS_IMU : public GPS
|
||||
{
|
||||
public:
|
||||
// Methods
|
||||
|
@ -1,6 +1,6 @@
|
||||
/*
|
||||
AP_GPS_MTK.cpp - Ublox GPS library for Arduino
|
||||
Code by Jordi MuÒoz and Jose Julio. DIYDrones.com
|
||||
GPS_MTK.cpp - Ublox GPS library for Arduino
|
||||
Code by Jordi Munoz and Jose Julio. DIYDrones.com
|
||||
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
|
||||
@ -28,6 +28,7 @@
|
||||
*/
|
||||
|
||||
#include "AP_GPS_MTK.h"
|
||||
#include "WProgram.h"
|
||||
|
||||
// Constructors ////////////////////////////////////////////////////////////////
|
||||
AP_GPS_MTK::AP_GPS_MTK()
|
||||
@ -38,6 +39,8 @@ AP_GPS_MTK::AP_GPS_MTK()
|
||||
// Public Methods //////////////////////////////////////////////////////////////
|
||||
void AP_GPS_MTK::init(void)
|
||||
{
|
||||
Serial.print("$PGCMD,16,0,0,0,0,0*6A\r\n");
|
||||
|
||||
ck_a = 0;
|
||||
ck_b = 0;
|
||||
step = 0;
|
||||
@ -146,15 +149,15 @@ AP_GPS_MTK::parse_gps(void)
|
||||
//Checking the UBX ID
|
||||
case 0x05: // ID Custom
|
||||
j = 0;
|
||||
lattitude= join_4_bytes(&buffer[j]); // lon * 10000000
|
||||
lattitude= join_4_bytes(&buffer[j]) * 10; // lon * 10000000
|
||||
j += 4;
|
||||
longitude = join_4_bytes(&buffer[j]); // lat * 10000000
|
||||
longitude = join_4_bytes(&buffer[j]) * 10; // lat * 10000000
|
||||
j += 4;
|
||||
altitude = join_4_bytes(&buffer[j]); // MSL
|
||||
j += 4;
|
||||
speed_3d = ground_speed = join_4_bytes(&buffer[j]);
|
||||
j += 4;
|
||||
ground_course = join_4_bytes(&buffer[j]);
|
||||
ground_course = join_4_bytes(&buffer[j]) / 10000;
|
||||
j += 4;
|
||||
num_sats = buffer[j];
|
||||
j++;
|
||||
|
@ -1,10 +1,10 @@
|
||||
#ifndef AP_GPS_MTK_h
|
||||
#define AP_GPS_MTK_h
|
||||
|
||||
#include <AP_GPS.h>
|
||||
#include <GPS.h>
|
||||
#define MAXPAYLOAD 32
|
||||
|
||||
class AP_GPS_MTK : public AP_GPS
|
||||
class AP_GPS_MTK : public GPS
|
||||
{
|
||||
public:
|
||||
// Methods
|
||||
|
@ -37,6 +37,7 @@
|
||||
NOTE : This code has been tested on a Locosys 20031 GPS receiver (MTK chipset)
|
||||
*/
|
||||
#include "AP_GPS_NMEA.h"
|
||||
#include "WProgram.h"
|
||||
|
||||
// Constructors ////////////////////////////////////////////////////////////////
|
||||
AP_GPS_NMEA::AP_GPS_NMEA()
|
||||
|
@ -1,10 +1,10 @@
|
||||
#ifndef AP_GPS_NMEA_h
|
||||
#define AP_GPS_NMEA_h
|
||||
|
||||
#include "AP_GPS.h"
|
||||
#include <GPS.h>
|
||||
#define GPS_BUFFERSIZE 120
|
||||
|
||||
class AP_GPS_NMEA : public AP_GPS
|
||||
class AP_GPS_NMEA : public GPS
|
||||
{
|
||||
public:
|
||||
// Methods
|
||||
@ -30,6 +30,4 @@ class AP_GPS_NMEA : public AP_GPS
|
||||
|
||||
};
|
||||
|
||||
extern AP_GPS_NMEA GPS;
|
||||
|
||||
#endif
|
@ -1,5 +1,5 @@
|
||||
/*
|
||||
AP_GPS_UBLOX.cpp - Ublox GPS library for Arduino
|
||||
GPS_UBLOX.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)
|
||||
|
||||
@ -34,6 +34,7 @@
|
||||
*/
|
||||
|
||||
#include "AP_GPS_UBLOX.h"
|
||||
#include "WProgram.h"
|
||||
|
||||
// Constructors ////////////////////////////////////////////////////////////////
|
||||
AP_GPS_UBLOX::AP_GPS_UBLOX()
|
||||
|
@ -1,10 +1,10 @@
|
||||
#ifndef GPS_UBLOX_h
|
||||
#define GPS_UBLOX_h
|
||||
#ifndef AP_GPS_UBLOX_h
|
||||
#define AP_GPS_UBLOX_h
|
||||
|
||||
#include <AP_GPS.h>
|
||||
#include <GPS.h>
|
||||
#define MAXPAYLOAD 60
|
||||
|
||||
class AP_GPS_UBLOX : public AP_GPS
|
||||
class AP_GPS_UBLOX : public GPS
|
||||
{
|
||||
public:
|
||||
// Methods
|
||||
|
Loading…
Reference in New Issue
Block a user