aboutsummaryrefslogtreecommitdiff
path: root/apps/gps/nmealib/nmea
diff options
context:
space:
mode:
Diffstat (limited to 'apps/gps/nmealib/nmea')
-rw-r--r--apps/gps/nmealib/nmea/config.h51
-rw-r--r--apps/gps/nmealib/nmea/context.h44
-rw-r--r--apps/gps/nmealib/nmea/generate.h44
-rw-r--r--apps/gps/nmealib/nmea/generator.h79
-rw-r--r--apps/gps/nmealib/nmea/gmath.h92
-rw-r--r--apps/gps/nmealib/nmea/info.h112
-rw-r--r--apps/gps/nmealib/nmea/nmea.h25
-rw-r--r--apps/gps/nmealib/nmea/parse.h39
-rw-r--r--apps/gps/nmealib/nmea/parser.h59
-rw-r--r--apps/gps/nmealib/nmea/sentence.h128
-rw-r--r--apps/gps/nmealib/nmea/time.h47
-rw-r--r--apps/gps/nmealib/nmea/tok.h31
-rw-r--r--apps/gps/nmealib/nmea/units.h30
13 files changed, 0 insertions, 781 deletions
diff --git a/apps/gps/nmealib/nmea/config.h b/apps/gps/nmealib/nmea/config.h
deleted file mode 100644
index 501466218..000000000
--- a/apps/gps/nmealib/nmea/config.h
+++ /dev/null
@@ -1,51 +0,0 @@
-/*
- *
- * NMEA library
- * URL: http://nmea.sourceforge.net
- * Author: Tim (xtimor@gmail.com)
- * Licence: http://www.gnu.org/licenses/lgpl.html
- * $Id: config.h 17 2008-03-11 11:56:11Z xtimor $
- *
- */
-
-#ifndef __NMEA_CONFIG_H__
-#define __NMEA_CONFIG_H__
-
-#define NMEA_VERSION ("0.5.3")
-#define NMEA_VERSION_MAJOR (0)
-#define NMEA_VERSION_MINOR (5)
-#define NMEA_VERSION_PATCH (3)
-
-#define NMEA_CONVSTR_BUF (256)
-#define NMEA_TIMEPARSE_BUF (256)
-
-#if defined(WINCE) || defined(UNDER_CE)
-# define NMEA_CE
-#endif
-
-#if defined(WIN32) || defined(NMEA_CE)
-# define NMEA_WIN
-#else
-# define NMEA_UNI
-#endif
-
-#if defined(NMEA_WIN) && (_MSC_VER >= 1400)
-# pragma warning(disable: 4996) /* declared deprecated */
-#endif
-
-#if defined(_MSC_VER)
-# define NMEA_POSIX(x) _##x
-# define NMEA_INLINE __inline
-#else
-# define NMEA_POSIX(x) x
-# define NMEA_INLINE inline
-#endif
-
-#if !defined(NDEBUG) && !defined(NMEA_CE)
-# include <assert.h>
-# define NMEA_ASSERT(x) assert(x)
-#else
-# define NMEA_ASSERT(x)
-#endif
-
-#endif /* __NMEA_CONFIG_H__ */
diff --git a/apps/gps/nmealib/nmea/context.h b/apps/gps/nmealib/nmea/context.h
deleted file mode 100644
index 06e558327..000000000
--- a/apps/gps/nmealib/nmea/context.h
+++ /dev/null
@@ -1,44 +0,0 @@
-/*
- *
- * NMEA library
- * URL: http://nmea.sourceforge.net
- * Author: Tim (xtimor@gmail.com)
- * Licence: http://www.gnu.org/licenses/lgpl.html
- * $Id: context.h 4 2007-08-27 13:11:03Z xtimor $
- *
- */
-
-#ifndef __NMEA_CONTEXT_H__
-#define __NMEA_CONTEXT_H__
-
-#include "config.h"
-
-#define NMEA_DEF_PARSEBUFF (1024)
-#define NMEA_MIN_PARSEBUFF (256)
-
-#ifdef __cplusplus
-extern "C" {
-#endif
-
-typedef void (*nmeaTraceFunc)(const char *str, int str_size);
-typedef void (*nmeaErrorFunc)(const char *str, int str_size);
-
-typedef struct _nmeaPROPERTY
-{
- nmeaTraceFunc trace_func;
- nmeaErrorFunc error_func;
- int parse_buff_size;
-
-} nmeaPROPERTY;
-
-nmeaPROPERTY * nmea_property(void);
-
-void nmea_trace(const char *str, ...);
-void nmea_trace_buff(const char *buff, int buff_size);
-void nmea_error(const char *str, ...);
-
-#ifdef __cplusplus
-}
-#endif
-
-#endif /* __NMEA_CONTEXT_H__ */
diff --git a/apps/gps/nmealib/nmea/generate.h b/apps/gps/nmealib/nmea/generate.h
deleted file mode 100644
index 9d7fdee51..000000000
--- a/apps/gps/nmealib/nmea/generate.h
+++ /dev/null
@@ -1,44 +0,0 @@
-/*
- *
- * NMEA library
- * URL: http://nmea.sourceforge.net
- * Author: Tim (xtimor@gmail.com)
- * Licence: http://www.gnu.org/licenses/lgpl.html
- * $Id: generate.h 4 2007-08-27 13:11:03Z xtimor $
- *
- */
-
-#ifndef __NMEA_GENERATE_H__
-#define __NMEA_GENERATE_H__
-
-#include "sentence.h"
-
-#ifdef __cplusplus
-extern "C" {
-#endif
-
-int nmea_generate(
- char *buff, int buff_sz, /* buffer */
- const nmeaINFO *info, /* source info */
- int generate_mask /* mask of sentence`s (e.g. GPGGA | GPGSA) */
- );
-
-int nmea_gen_GPGGA(char *buff, int buff_sz, nmeaGPGGA *pack);
-int nmea_gen_GPGSA(char *buff, int buff_sz, nmeaGPGSA *pack);
-int nmea_gen_GPGSV(char *buff, int buff_sz, nmeaGPGSV *pack);
-int nmea_gen_GPRMC(char *buff, int buff_sz, nmeaGPRMC *pack);
-int nmea_gen_GPVTG(char *buff, int buff_sz, nmeaGPVTG *pack);
-
-void nmea_info2GPGGA(const nmeaINFO *info, nmeaGPGGA *pack);
-void nmea_info2GPGSA(const nmeaINFO *info, nmeaGPGSA *pack);
-void nmea_info2GPRMC(const nmeaINFO *info, nmeaGPRMC *pack);
-void nmea_info2GPVTG(const nmeaINFO *info, nmeaGPVTG *pack);
-
-int nmea_gsv_npack(int sat_count);
-void nmea_info2GPGSV(const nmeaINFO *info, nmeaGPGSV *pack, int pack_idx);
-
-#ifdef __cplusplus
-}
-#endif
-
-#endif /* __NMEA_GENERATE_H__ */
diff --git a/apps/gps/nmealib/nmea/generator.h b/apps/gps/nmealib/nmea/generator.h
deleted file mode 100644
index a97b91b13..000000000
--- a/apps/gps/nmealib/nmea/generator.h
+++ /dev/null
@@ -1,79 +0,0 @@
-/*
- *
- * NMEA library
- * URL: http://nmea.sourceforge.net
- * Author: Tim (xtimor@gmail.com)
- * Licence: http://www.gnu.org/licenses/lgpl.html
- * $Id: generator.h 4 2007-08-27 13:11:03Z xtimor $
- *
- */
-
-#ifndef __NMEA_GENERATOR_H__
-#define __NMEA_GENERATOR_H__
-
-#include "info.h"
-
-#ifdef __cplusplus
-extern "C" {
-#endif
-
-/*
- * high level
- */
-
-struct _nmeaGENERATOR;
-
-enum nmeaGENTYPE
-{
- NMEA_GEN_NOISE = 0,
- NMEA_GEN_STATIC,
- NMEA_GEN_ROTATE,
-
- NMEA_GEN_SAT_STATIC,
- NMEA_GEN_SAT_ROTATE,
- NMEA_GEN_POS_RANDMOVE,
-
- NMEA_GEN_LAST
-};
-
-struct _nmeaGENERATOR * nmea_create_generator(int type, nmeaINFO *info);
-void nmea_destroy_generator(struct _nmeaGENERATOR *gen);
-
-int nmea_generate_from(
- char *buff, int buff_sz, /* buffer */
- nmeaINFO *info, /* source info */
- struct _nmeaGENERATOR *gen, /* generator */
- int generate_mask /* mask of sentence`s (e.g. GPGGA | GPGSA) */
- );
-
-/*
- * low level
- */
-
-typedef int (*nmeaNMEA_GEN_INIT)(struct _nmeaGENERATOR *gen, nmeaINFO *info);
-typedef int (*nmeaNMEA_GEN_LOOP)(struct _nmeaGENERATOR *gen, nmeaINFO *info);
-typedef int (*nmeaNMEA_GEN_RESET)(struct _nmeaGENERATOR *gen, nmeaINFO *info);
-typedef int (*nmeaNMEA_GEN_DESTROY)(struct _nmeaGENERATOR *gen);
-
-typedef struct _nmeaGENERATOR
-{
- void *gen_data;
- nmeaNMEA_GEN_INIT init_call;
- nmeaNMEA_GEN_LOOP loop_call;
- nmeaNMEA_GEN_RESET reset_call;
- nmeaNMEA_GEN_DESTROY destroy_call;
- struct _nmeaGENERATOR *next;
-
-} nmeaGENERATOR;
-
-int nmea_gen_init(nmeaGENERATOR *gen, nmeaINFO *info);
-int nmea_gen_loop(nmeaGENERATOR *gen, nmeaINFO *info);
-int nmea_gen_reset(nmeaGENERATOR *gen, nmeaINFO *info);
-void nmea_gen_destroy(nmeaGENERATOR *gen);
-void nmea_gen_add(nmeaGENERATOR *to, nmeaGENERATOR *gen);
-
-#ifdef __cplusplus
-}
-#endif
-
-#endif /* __NMEA_GENERATOR_H__ */
diff --git a/apps/gps/nmealib/nmea/gmath.h b/apps/gps/nmealib/nmea/gmath.h
deleted file mode 100644
index 3133b7228..000000000
--- a/apps/gps/nmealib/nmea/gmath.h
+++ /dev/null
@@ -1,92 +0,0 @@
-/*
- *
- * NMEA library
- * URL: http://nmea.sourceforge.net
- * Author: Tim (xtimor@gmail.com)
- * Licence: http://www.gnu.org/licenses/lgpl.html
- * $Id: gmath.h 17 2008-03-11 11:56:11Z xtimor $
- *
- */
-
-#ifndef __NMEA_GMATH_H__
-#define __NMEA_GMATH_H__
-
-#include "info.h"
-
-#define NMEA_PI (3.141592653589793) /**< PI value */
-#define NMEA_PI180 (NMEA_PI / 180) /**< PI division by 180 */
-#define NMEA_EARTHRADIUS_KM (6378) /**< Earth's mean radius in km */
-#define NMEA_EARTHRADIUS_M (NMEA_EARTHRADIUS_KM * 1000) /**< Earth's mean radius in m */
-#define NMEA_EARTH_SEMIMAJORAXIS_M (6378137.0) /**< Earth's semi-major axis in m according WGS84 */
-#define NMEA_EARTH_SEMIMAJORAXIS_KM (NMEA_EARTHMAJORAXIS_KM / 1000) /**< Earth's semi-major axis in km according WGS 84 */
-#define NMEA_EARTH_FLATTENING (1 / 298.257223563) /**< Earth's flattening according WGS 84 */
-#define NMEA_DOP_FACTOR (5) /**< Factor for translating DOP to meters */
-
-#ifdef __cplusplus
-extern "C" {
-#endif
-
-/*
- * degree VS radian
- */
-
-float nmea_degree2radian(float val);
-float nmea_radian2degree(float val);
-
-/*
- * NDEG (NMEA degree)
- */
-
-float nmea_ndeg2degree(float val);
-float nmea_degree2ndeg(float val);
-
-float nmea_ndeg2radian(float val);
-float nmea_radian2ndeg(float val);
-
-/*
- * DOP
- */
-
-float nmea_calc_pdop(float hdop, float vdop);
-float nmea_dop2meters(float dop);
-float nmea_meters2dop(float meters);
-
-/*
- * positions work
- */
-
-void nmea_info2pos(const nmeaINFO *info, nmeaPOS *pos);
-void nmea_pos2info(const nmeaPOS *pos, nmeaINFO *info);
-
-float nmea_distance(
- const nmeaPOS *from_pos,
- const nmeaPOS *to_pos
- );
-
-float nmea_distance_ellipsoid(
- const nmeaPOS *from_pos,
- const nmeaPOS *to_pos,
- float *from_azimuth,
- float *to_azimuth
- );
-
-int nmea_move_horz(
- const nmeaPOS *start_pos,
- nmeaPOS *end_pos,
- float azimuth,
- float distance
- );
-
-int nmea_move_horz_ellipsoid(
- const nmeaPOS *start_pos,
- nmeaPOS *end_pos,
- float azimuth,
- float distance,
- float *end_azimuth
- );
-
-#ifdef __cplusplus
-}
-#endif
-
-#endif /* __NMEA_GMATH_H__ */
diff --git a/apps/gps/nmealib/nmea/info.h b/apps/gps/nmealib/nmea/info.h
deleted file mode 100644
index 09ccd4c09..000000000
--- a/apps/gps/nmealib/nmea/info.h
+++ /dev/null
@@ -1,112 +0,0 @@
-/*
- *
- * NMEA library
- * URL: http://nmea.sourceforge.net
- * Author: Tim (xtimor@gmail.com)
- * Licence: http://www.gnu.org/licenses/lgpl.html
- * $Id: info.h 10 2007-11-15 14:50:15Z xtimor $
- *
- */
-
-/*! \file */
-
-#ifndef __NMEA_INFO_H__
-#define __NMEA_INFO_H__
-
-#include "time.h"
-
-#define NMEA_SIG_BAD (0)
-#define NMEA_SIG_LOW (1)
-#define NMEA_SIG_MID (2)
-#define NMEA_SIG_HIGH (3)
-
-#define NMEA_FIX_BAD (1)
-#define NMEA_FIX_2D (2)
-#define NMEA_FIX_3D (3)
-
-#define NMEA_MAXSAT (12)
-#define NMEA_SATINPACK (4)
-#define NMEA_NSATPACKS (NMEA_MAXSAT / NMEA_SATINPACK)
-
-#define NMEA_DEF_LAT (5001.2621)
-#define NMEA_DEF_LON (3613.0595)
-
-#ifdef __cplusplus
-extern "C" {
-#endif
-
-/**
- * Position data in fractional degrees or radians
- */
-typedef struct _nmeaPOS
-{
- float lat; /**< Latitude */
- float lon; /**< Longitude */
-
-} nmeaPOS;
-
-/**
- * Information about satellite
- * @see nmeaSATINFO
- * @see nmeaGPGSV
- */
-typedef struct _nmeaSATELLITE
-{
- int id; /**< Satellite PRN number */
- int in_use; /**< Used in position fix */
- int elv; /**< Elevation in degrees, 90 maximum */
- int azimuth; /**< Azimuth, degrees from true north, 000 to 359 */
- int sig; /**< Signal, 00-99 dB */
-
-} nmeaSATELLITE;
-
-/**
- * Information about all satellites in view
- * @see nmeaINFO
- * @see nmeaGPGSV
- */
-typedef struct _nmeaSATINFO
-{
- int inuse; /**< Number of satellites in use (not those in view) */
- int inview; /**< Total number of satellites in view */
- nmeaSATELLITE sat[NMEA_MAXSAT]; /**< Satellites information */
-
-} nmeaSATINFO;
-
-/**
- * Summary GPS information from all parsed packets,
- * used also for generating NMEA stream
- * @see nmea_parse
- * @see nmea_GPGGA2info, nmea_...2info
- */
-typedef struct _nmeaINFO
-{
- int smask; /**< Mask specifying types of packages from which data have been obtained */
-
- nmeaTIME utc; /**< UTC of position */
-
- int sig; /**< GPS quality indicator (0 = Invalid; 1 = Fix; 2 = Differential, 3 = Sensitive) */
- int fix; /**< Operating mode, used for navigation (1 = Fix not available; 2 = 2D; 3 = 3D) */
-
- float PDOP; /**< Position Dilution Of Precision */
- float HDOP; /**< Horizontal Dilution Of Precision */
- float VDOP; /**< Vertical Dilution Of Precision */
-
- float lat; /**< Latitude in NDEG - +/-[degree][min].[sec/60] */
- float lon; /**< Longitude in NDEG - +/-[degree][min].[sec/60] */
- float elv; /**< Antenna altitude above/below mean sea level (geoid) in meters */
- float speed; /**< Speed over the ground in kilometers/hour */
- float direction; /**< Track angle in degrees True */
- float declination; /**< Magnetic variation degrees (Easterly var. subtracts from true course) */
-
- nmeaSATINFO satinfo; /**< Satellites information */
-
-} nmeaINFO;
-
-void nmea_zero_INFO(nmeaINFO *info);
-
-#ifdef __cplusplus
-}
-#endif
-
-#endif /* __NMEA_INFO_H__ */
diff --git a/apps/gps/nmealib/nmea/nmea.h b/apps/gps/nmealib/nmea/nmea.h
deleted file mode 100644
index 62692230f..000000000
--- a/apps/gps/nmealib/nmea/nmea.h
+++ /dev/null
@@ -1,25 +0,0 @@
-/*
- *
- * NMEA library
- * URL: http://nmea.sourceforge.net
- * Author: Tim (xtimor@gmail.com)
- * Licence: http://www.gnu.org/licenses/lgpl.html
- * $Id: nmea.h 17 2008-03-11 11:56:11Z xtimor $
- *
- */
-
-#ifndef __NMEA_H__
-#define __NMEA_H__
-
-#include "./config.h"
-#include "./units.h"
-#include "./gmath.h"
-#include "./info.h"
-#include "./sentence.h"
-#include "./generate.h"
-#include "./generator.h"
-#include "./parse.h"
-#include "./parser.h"
-#include "./context.h"
-
-#endif /* __NMEA_H__ */
diff --git a/apps/gps/nmealib/nmea/parse.h b/apps/gps/nmealib/nmea/parse.h
deleted file mode 100644
index 3e6b425db..000000000
--- a/apps/gps/nmealib/nmea/parse.h
+++ /dev/null
@@ -1,39 +0,0 @@
-/*
- *
- * NMEA library
- * URL: http://nmea.sourceforge.net
- * Author: Tim (xtimor@gmail.com)
- * Licence: http://www.gnu.org/licenses/lgpl.html
- * $Id: parse.h 4 2007-08-27 13:11:03Z xtimor $
- *
- */
-
-#ifndef __NMEA_PARSE_H__
-#define __NMEA_PARSE_H__
-
-#include "sentence.h"
-
-#ifdef __cplusplus
-extern "C" {
-#endif
-
-int nmea_pack_type(const char *buff, int buff_sz);
-int nmea_find_tail(const char *buff, int buff_sz, int *res_crc);
-
-int nmea_parse_GPGGA(const char *buff, int buff_sz, nmeaGPGGA *pack);
-int nmea_parse_GPGSA(const char *buff, int buff_sz, nmeaGPGSA *pack);
-int nmea_parse_GPGSV(const char *buff, int buff_sz, nmeaGPGSV *pack);
-int nmea_parse_GPRMC(const char *buff, int buff_sz, nmeaGPRMC *pack);
-int nmea_parse_GPVTG(const char *buff, int buff_sz, nmeaGPVTG *pack);
-
-void nmea_GPGGA2info(nmeaGPGGA *pack, nmeaINFO *info);
-void nmea_GPGSA2info(nmeaGPGSA *pack, nmeaINFO *info);
-void nmea_GPGSV2info(nmeaGPGSV *pack, nmeaINFO *info);
-void nmea_GPRMC2info(nmeaGPRMC *pack, nmeaINFO *info);
-void nmea_GPVTG2info(nmeaGPVTG *pack, nmeaINFO *info);
-
-#ifdef __cplusplus
-}
-#endif
-
-#endif /* __NMEA_PARSE_H__ */
diff --git a/apps/gps/nmealib/nmea/parser.h b/apps/gps/nmealib/nmea/parser.h
deleted file mode 100644
index 51a3fab7f..000000000
--- a/apps/gps/nmealib/nmea/parser.h
+++ /dev/null
@@ -1,59 +0,0 @@
-/*
- *
- * NMEA library
- * URL: http://nmea.sourceforge.net
- * Author: Tim (xtimor@gmail.com)
- * Licence: http://www.gnu.org/licenses/lgpl.html
- * $Id: parser.h 4 2007-08-27 13:11:03Z xtimor $
- *
- */
-
-#ifndef __NMEA_PARSER_H__
-#define __NMEA_PARSER_H__
-
-#include "info.h"
-
-#ifdef __cplusplus
-extern "C" {
-#endif
-
-/*
- * high level
- */
-
-typedef struct _nmeaPARSER
-{
- void *top_node;
- void *end_node;
- unsigned char *buffer;
- int buff_size;
- int buff_use;
-
-} nmeaPARSER;
-
-int nmea_parser_init(nmeaPARSER *parser);
-void nmea_parser_destroy(nmeaPARSER *parser);
-
-int nmea_parse(
- nmeaPARSER *parser,
- const char *buff, int buff_sz,
- nmeaINFO *info
- );
-
-/*
- * low level
- */
-
-int nmea_parser_push(nmeaPARSER *parser, const char *buff, int buff_sz);
-int nmea_parser_top(nmeaPARSER *parser);
-int nmea_parser_pop(nmeaPARSER *parser, void **pack_ptr);
-int nmea_parser_peek(nmeaPARSER *parser, void **pack_ptr);
-int nmea_parser_drop(nmeaPARSER *parser);
-int nmea_parser_buff_clear(nmeaPARSER *parser);
-int nmea_parser_queue_clear(nmeaPARSER *parser);
-
-#ifdef __cplusplus
-}
-#endif
-
-#endif /* __NMEA_PARSER_H__ */
diff --git a/apps/gps/nmealib/nmea/sentence.h b/apps/gps/nmealib/nmea/sentence.h
deleted file mode 100644
index 2aa975c71..000000000
--- a/apps/gps/nmealib/nmea/sentence.h
+++ /dev/null
@@ -1,128 +0,0 @@
-/*
- *
- * NMEA library
- * URL: http://nmea.sourceforge.net
- * Author: Tim (xtimor@gmail.com)
- * Licence: http://www.gnu.org/licenses/lgpl.html
- * $Id: sentence.h 17 2008-03-11 11:56:11Z xtimor $
- *
- */
-
-/*! \file */
-
-#ifndef __NMEA_SENTENCE_H__
-#define __NMEA_SENTENCE_H__
-
-#include "info.h"
-
-#ifdef __cplusplus
-extern "C" {
-#endif
-
-/**
- * NMEA packets type which parsed and generated by library
- */
-enum nmeaPACKTYPE
-{
- GPNON = 0x0000, /**< Unknown packet type. */
- GPGGA = 0x0001, /**< GGA - Essential fix data which provide 3D location and accuracy data. */
- GPGSA = 0x0002, /**< GSA - GPS receiver operating mode, SVs used for navigation, and DOP values. */
- GPGSV = 0x0004, /**< GSV - Number of SVs in view, PRN numbers, elevation, azimuth & SNR values. */
- GPRMC = 0x0008, /**< RMC - Recommended Minimum Specific GPS/TRANSIT Data. */
- GPVTG = 0x0010 /**< VTG - Actual track made good and speed over ground. */
-};
-
-/**
- * GGA packet information structure (Global Positioning System Fix Data)
- */
-typedef struct _nmeaGPGGA
-{
- nmeaTIME utc; /**< UTC of position (just time) */
- float lat; /**< Latitude in NDEG - [degree][min].[sec/60] */
- char ns; /**< [N]orth or [S]outh */
- float lon; /**< Longitude in NDEG - [degree][min].[sec/60] */
- char ew; /**< [E]ast or [W]est */
- int sig; /**< GPS quality indicator (0 = Invalid; 1 = Fix; 2 = Differential, 3 = Sensitive) */
- int satinuse; /**< Number of satellites in use (not those in view) */
- float HDOP; /**< Horizontal dilution of precision */
- float elv; /**< Antenna altitude above/below mean sea level (geoid) */
- char elv_units; /**< [M]eters (Antenna height unit) */
- float diff; /**< Geoidal separation (Diff. between WGS-84 earth ellipsoid and mean sea level. '-' = geoid is below WGS-84 ellipsoid) */
- char diff_units; /**< [M]eters (Units of geoidal separation) */
- float dgps_age; /**< Time in seconds since last DGPS update */
- int dgps_sid; /**< DGPS station ID number */
-
-} nmeaGPGGA;
-
-/**
- * GSA packet information structure (Satellite status)
- */
-typedef struct _nmeaGPGSA
-{
- char fix_mode; /**< Mode (M = Manual, forced to operate in 2D or 3D; A = Automatic, 3D/2D) */
- int fix_type; /**< Type, used for navigation (1 = Fix not available; 2 = 2D; 3 = 3D) */
- int sat_prn[NMEA_MAXSAT]; /**< PRNs of satellites used in position fix (null for unused fields) */
- float PDOP; /**< Dilution of precision */
- float HDOP; /**< Horizontal dilution of precision */
- float VDOP; /**< Vertical dilution of precision */
-
-} nmeaGPGSA;
-
-/**
- * GSV packet information structure (Satellites in view)
- */
-typedef struct _nmeaGPGSV
-{
- int pack_count; /**< Total number of messages of this type in this cycle */
- int pack_index; /**< Message number */
- int sat_count; /**< Total number of satellites in view */
- nmeaSATELLITE sat_data[NMEA_SATINPACK];
-
-} nmeaGPGSV;
-
-/**
- * RMC packet information structure (Recommended Minimum sentence C)
- */
-typedef struct _nmeaGPRMC
-{
- nmeaTIME utc; /**< UTC of position */
- char status; /**< Status (A = active or V = void) */
- float lat; /**< Latitude in NDEG - [degree][min].[sec/60] */
- char ns; /**< [N]orth or [S]outh */
- float lon; /**< Longitude in NDEG - [degree][min].[sec/60] */
- char ew; /**< [E]ast or [W]est */
- float speed; /**< Speed over the ground in knots */
- float direction; /**< Track angle in degrees True */
- float declination; /**< Magnetic variation degrees (Easterly var. subtracts from true course) */
- char declin_ew; /**< [E]ast or [W]est */
- char mode; /**< Mode indicator of fix type (A = autonomous, D = differential, E = estimated, N = not valid, S = simulator) */
-
-} nmeaGPRMC;
-
-/**
- * VTG packet information structure (Track made good and ground speed)
- */
-typedef struct _nmeaGPVTG
-{
- float dir; /**< True track made good (degrees) */
- char dir_t; /**< Fixed text 'T' indicates that track made good is relative to true north */
- float dec; /**< Magnetic track made good */
- char dec_m; /**< Fixed text 'M' */
- float spn; /**< Ground speed, knots */
- char spn_n; /**< Fixed text 'N' indicates that speed over ground is in knots */
- float spk; /**< Ground speed, kilometers per hour */
- char spk_k; /**< Fixed text 'K' indicates that speed over ground is in kilometers/hour */
-
-} nmeaGPVTG;
-
-void nmea_zero_GPGGA(nmeaGPGGA *pack);
-void nmea_zero_GPGSA(nmeaGPGSA *pack);
-void nmea_zero_GPGSV(nmeaGPGSV *pack);
-void nmea_zero_GPRMC(nmeaGPRMC *pack);
-void nmea_zero_GPVTG(nmeaGPVTG *pack);
-
-#ifdef __cplusplus
-}
-#endif
-
-#endif /* __NMEA_SENTENCE_H__ */
diff --git a/apps/gps/nmealib/nmea/time.h b/apps/gps/nmealib/nmea/time.h
deleted file mode 100644
index bbe59f65c..000000000
--- a/apps/gps/nmealib/nmea/time.h
+++ /dev/null
@@ -1,47 +0,0 @@
-/*
- *
- * NMEA library
- * URL: http://nmea.sourceforge.net
- * Author: Tim (xtimor@gmail.com)
- * Licence: http://www.gnu.org/licenses/lgpl.html
- * $Id: time.h 4 2007-08-27 13:11:03Z xtimor $
- *
- */
-
-/*! \file */
-
-#ifndef __NMEA_TIME_H__
-#define __NMEA_TIME_H__
-
-#include "config.h"
-
-#ifdef __cplusplus
-extern "C" {
-#endif
-
-/**
- * Date and time data
- * @see nmea_time_now
- */
-typedef struct _nmeaTIME
-{
- int year; /**< Years since 1900 */
- int mon; /**< Months since January - [0,11] */
- int day; /**< Day of the month - [1,31] */
- int hour; /**< Hours since midnight - [0,23] */
- int min; /**< Minutes after the hour - [0,59] */
- int sec; /**< Seconds after the minute - [0,59] */
- int hsec; /**< Hundredth part of second - [0,99] */
-
-} nmeaTIME;
-
-/**
- * \brief Get time now to nmeaTIME structure
- */
-void nmea_time_now(nmeaTIME *t);
-
-#ifdef __cplusplus
-}
-#endif
-
-#endif /* __NMEA_TIME_H__ */
diff --git a/apps/gps/nmealib/nmea/tok.h b/apps/gps/nmealib/nmea/tok.h
deleted file mode 100644
index 8f948dd2d..000000000
--- a/apps/gps/nmealib/nmea/tok.h
+++ /dev/null
@@ -1,31 +0,0 @@
-/*
- *
- * NMEA library
- * URL: http://nmea.sourceforge.net
- * Author: Tim (xtimor@gmail.com)
- * Licence: http://www.gnu.org/licenses/lgpl.html
- * $Id: tok.h 4 2007-08-27 13:11:03Z xtimor $
- *
- */
-
-#ifndef __NMEA_TOK_H__
-#define __NMEA_TOK_H__
-
-#include "config.h"
-#include <string.h>
-
-#ifdef __cplusplus
-extern "C" {
-#endif
-
-int nmea_calc_crc(const char *buff, int buff_sz);
-int nmea_atoi(const char *str, int str_sz, int radix);
-float nmea_atof(const char *str, int str_sz);
-int nmea_printf(char *buff, int buff_sz, const char *format, ...);
-int nmea_scanf(const char *buff, int buff_sz, const char *format, ...);
-
-#ifdef __cplusplus
-}
-#endif
-
-#endif /* __NMEA_TOK_H__ */
diff --git a/apps/gps/nmealib/nmea/units.h b/apps/gps/nmealib/nmea/units.h
deleted file mode 100644
index 767f980e2..000000000
--- a/apps/gps/nmealib/nmea/units.h
+++ /dev/null
@@ -1,30 +0,0 @@
-/*
- *
- * NMEA library
- * URL: http://nmea.sourceforge.net
- * Author: Tim (xtimor@gmail.com)
- * Licence: http://www.gnu.org/licenses/lgpl.html
- * $Id: units.h 4 2007-08-27 13:11:03Z xtimor $
- *
- */
-
-#ifndef __NMEA_UNITS_H__
-#define __NMEA_UNITS_H__
-
-#include "config.h"
-
-/*
- * Distance units
- */
-
-#define NMEA_TUD_YARDS (1.0936) /**< Yeards, meter * NMEA_TUD_YARDS = yard */
-#define NMEA_TUD_KNOTS (1.852) /**< Knots, kilometer / NMEA_TUD_KNOTS = knot */
-#define NMEA_TUD_MILES (1.609) /**< Miles, kilometer / NMEA_TUD_MILES = mile */
-
-/*
- * Speed units
- */
-
-#define NMEA_TUS_MS (3.6) /**< Meters per seconds, (k/h) / NMEA_TUS_MS= (m/s) */
-
-#endif /* __NMEA_UNITS_H__ */