├── extras ├── doc │ ├── images │ │ ├── example.png │ │ ├── GPS Timing 0.jpg │ │ ├── GPS Timing 1.jpg │ │ └── GPS Timing 2.jpg │ ├── readme.txt │ ├── Acknowledgements.md │ ├── Program.md │ ├── License.md │ ├── Garmin.md │ ├── Coherency.md │ ├── RAM.md │ ├── CharOriented.md │ ├── Tradeoffs.md │ ├── Performance.md │ ├── Extending.md │ ├── Location.md │ ├── ublox.md │ ├── Merging.md │ ├── Choosing.md │ └── Examples.md └── configs │ ├── Full │ ├── GPSfix_cfg.h │ └── NeoGPS_cfg.h │ ├── Nominal │ ├── GPSfix_cfg.h │ └── NeoGPS_cfg.h │ ├── PUBX │ ├── GPSfix_cfg.h │ └── NeoGPS_cfg.h │ ├── DTL │ ├── GPSfix_cfg.h │ └── NeoGPS_cfg.h │ ├── Speed │ ├── GPSfix_cfg.h │ └── NeoGPS_cfg.h │ └── Minimal │ ├── GPSfix_cfg.h │ └── NeoGPS_cfg.h ├── library.properties ├── .gitattributes ├── src ├── Garmin │ ├── PGRM_cfg.h │ ├── GrmNMEA.h │ └── GrmNMEA.cpp ├── ublox │ ├── PUBX_cfg.h │ ├── ubxmsg.cpp │ ├── ubx_cfg.h │ ├── ubxNMEA.h │ └── ubxNMEA.cpp ├── GPSTime.cpp ├── CosaCompat.h ├── GPSfix_cfg.h ├── Streamers.h ├── DMS.h ├── GPSTime.h ├── DMS.cpp ├── Location.h ├── NeoGPS_cfg.h ├── Location.cpp ├── NeoTime.cpp └── NeoTime.h ├── .gitignore ├── examples ├── NMEAblink │ └── NMEAblink.ino ├── NMEAsimple │ └── NMEAsimple.ino ├── NMEA_isr │ └── NMEA_isr.ino ├── NMEAdistance │ └── NMEAdistance.ino ├── NMEAbenchmark │ └── NMEAbenchmark.ino ├── NMEAGSV │ └── NMEAGSV.ino ├── NMEAlocDMS │ └── NMEAlocDMS.ino ├── PGRM │ └── PGRM.ino ├── SyncTime │ └── SyncTime.ino ├── PUBX │ └── PUBX.ino ├── NMEAloc │ └── NMEAloc.ino ├── NMEAtimezone │ └── NMEAtimezone.ino ├── NMEA │ └── NMEA.ino ├── Tabular │ └── Tabular.ino ├── NMEArevGeoCache │ └── NMEArevGeoCache.ino └── NMEAorder │ └── NMEAorder.ino └── README.md /extras/doc/images/example.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/SlashDevin/NeoGPS/HEAD/extras/doc/images/example.png -------------------------------------------------------------------------------- /extras/doc/images/GPS Timing 0.jpg: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/SlashDevin/NeoGPS/HEAD/extras/doc/images/GPS Timing 0.jpg -------------------------------------------------------------------------------- /extras/doc/images/GPS Timing 1.jpg: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/SlashDevin/NeoGPS/HEAD/extras/doc/images/GPS Timing 1.jpg -------------------------------------------------------------------------------- /extras/doc/images/GPS Timing 2.jpg: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/SlashDevin/NeoGPS/HEAD/extras/doc/images/GPS Timing 2.jpg -------------------------------------------------------------------------------- /extras/doc/readme.txt: -------------------------------------------------------------------------------- 1 | These .MD files are in github markdown format. They are intended to be read on the github website, as linked from the top repository page. 2 | -------------------------------------------------------------------------------- /extras/doc/Acknowledgements.md: -------------------------------------------------------------------------------- 1 | Acknowledgements 2 | ========== 3 | Mikal Hart's [TinyGPS](https://github.com/mikalhart/TinyGPS) for the generic `decode` approach. 4 | 5 | tht's [initial implementation](http://forum.arduino.cc/index.php?topic=150299.msg1863220#msg1863220) of a Cosa `IOStream::Device`. 6 | -------------------------------------------------------------------------------- /library.properties: -------------------------------------------------------------------------------- 1 | name=NeoGPS 2 | version=4.2.9 3 | author=SlashDevin 4 | maintainer=SlashDevin 5 | sentence=NMEA and ublox GPS parser, configurable to use as few as 10 bytes of RAM 6 | paragraph=Faster and smaller than all other GPS parsers 7 | category=Communication 8 | url=https://github.com/SlashDevin/NeoGPS 9 | architectures=avr,samd,sam,esp8266,arc32,esp32 10 | includes=NMEAGPS.h 11 | -------------------------------------------------------------------------------- /extras/doc/Program.md: -------------------------------------------------------------------------------- 1 | Program Space requirements 2 | ======= 3 | 4 | The **Minimal** configuration requires 866 bytes. 5 | 6 | The **DTL** configuration requires 2072 bytes. 7 | 8 | The **Nominal** configuration requires 2800 bytes. TinyGPS uses about 2400 bytes. TinyGPS++ uses about 2700 bytes. 9 | 10 | The **Full** configuration requires 3462 bytes. 11 | 12 | (All configuration numbers include 166 bytes PROGMEM.) 13 | 14 | -------------------------------------------------------------------------------- /.gitattributes: -------------------------------------------------------------------------------- 1 | # Auto detect text files and perform LF normalization 2 | * text=auto 3 | 4 | # Custom for Visual Studio 5 | *.cs diff=csharp 6 | 7 | # Standard to msysgit 8 | *.doc diff=astextplain 9 | *.DOC diff=astextplain 10 | *.docx diff=astextplain 11 | *.DOCX diff=astextplain 12 | *.dot diff=astextplain 13 | *.DOT diff=astextplain 14 | *.pdf diff=astextplain 15 | *.PDF diff=astextplain 16 | *.rtf diff=astextplain 17 | *.RTF diff=astextplain 18 | -------------------------------------------------------------------------------- /src/Garmin/PGRM_cfg.h: -------------------------------------------------------------------------------- 1 | #ifndef PGRM_CFG_H 2 | #define PGRM_CFG_H 3 | 4 | //------------------------------------------------------------ 5 | // Enable/disable the parsing of specific proprietary NMEA sentences. 6 | // 7 | // Configuring out a sentence prevents its fields from being parsed. 8 | // However, the sentence type may still be recognized by /decode/ and 9 | // stored in member /nmeaMessage/. No valid flags would be available. 10 | 11 | //#define GARMINGPS_PARSE_F 12 | 13 | #endif -------------------------------------------------------------------------------- /src/ublox/PUBX_cfg.h: -------------------------------------------------------------------------------- 1 | #ifndef PUBX_CFG_H 2 | #define PUBX_CFG_H 3 | 4 | //------------------------------------------------------------ 5 | // Enable/disable the parsing of specific proprietary NMEA sentences. 6 | // 7 | // Configuring out a sentence prevents its fields from being parsed. 8 | // However, the sentence type may still be recognized by /decode/ and 9 | // stored in member /nmeaMessage/. No valid flags would be available. 10 | 11 | #define NMEAGPS_PARSE_PUBX_00 12 | //#define NMEAGPS_PARSE_PUBX_04 13 | 14 | #endif -------------------------------------------------------------------------------- /extras/doc/License.md: -------------------------------------------------------------------------------- 1 | ### License: 2 | 3 | **NeoGPS** 4 | 5 | Copyright (C) 2014-2017, SlashDevin 6 | 7 | NeoGPS is free software: you can redistribute it and/or modify 8 | it under the terms of the GNU General Public License as published by 9 | the Free Software Foundation, either version 3 of the License, or 10 | (at your option) any later version. 11 | 12 | NeoGPS is distributed in the hope that it will be useful, 13 | but WITHOUT ANY WARRANTY; without even the implied warranty of 14 | MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the 15 | GNU General Public License for more details. 16 | 17 | You should have received a copy of the GNU General Public License 18 | along with NeoGPS. If not, see . 19 | -------------------------------------------------------------------------------- /.gitignore: -------------------------------------------------------------------------------- 1 | # Windows image file caches 2 | Thumbs.db 3 | ehthumbs.db 4 | 5 | # Folder config file 6 | Desktop.ini 7 | 8 | # Recycle Bin used on file shares 9 | $RECYCLE.BIN/ 10 | 11 | # Windows Installer files 12 | *.cab 13 | *.msi 14 | *.msm 15 | *.msp 16 | 17 | # Windows shortcuts 18 | *.lnk 19 | 20 | # ========================= 21 | # Operating System Files 22 | # ========================= 23 | 24 | # OSX 25 | # ========================= 26 | 27 | .DS_Store 28 | .AppleDouble 29 | .LSOverride 30 | 31 | # Thumbnails 32 | ._* 33 | 34 | # Files that might appear on external disk 35 | .Spotlight-V100 36 | .Trashes 37 | 38 | # Directories potentially created on remote AFP share 39 | .AppleDB 40 | .AppleDesktop 41 | Network Trash Folder 42 | Temporary Items 43 | .apdisk 44 | -------------------------------------------------------------------------------- /src/GPSTime.cpp: -------------------------------------------------------------------------------- 1 | // Copyright (C) 2014-2017, SlashDevin 2 | // 3 | // This file is part of NeoGPS 4 | // 5 | // NeoGPS is free software: you can redistribute it and/or modify 6 | // it under the terms of the GNU General Public License as published by 7 | // the Free Software Foundation, either version 3 of the License, or 8 | // (at your option) any later version. 9 | // 10 | // NeoGPS is distributed in the hope that it will be useful, 11 | // but WITHOUT ANY WARRANTY; without even the implied warranty of 12 | // MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the 13 | // GNU General Public License for more details. 14 | // 15 | // You should have received a copy of the GNU General Public License 16 | // along with NeoGPS. If not, see . 17 | 18 | #include "GPSTime.h" 19 | 20 | uint8_t GPSTime::leap_seconds = 0; 21 | NeoGPS::clock_t GPSTime::s_start_of_week = 0; 22 | -------------------------------------------------------------------------------- /src/CosaCompat.h: -------------------------------------------------------------------------------- 1 | #ifndef COSACOMPAT_H 2 | #define COSACOMPAT_H 3 | 4 | // Copyright (C) 2014-2017, SlashDevin 5 | // 6 | // This file is part of NeoGPS 7 | // 8 | // NeoGPS is free software: you can redistribute it and/or modify 9 | // it under the terms of the GNU General Public License as published by 10 | // the Free Software Foundation, either version 3 of the License, or 11 | // (at your option) any later version. 12 | // 13 | // NeoGPS is distributed in the hope that it will be useful, 14 | // but WITHOUT ANY WARRANTY; without even the implied warranty of 15 | // MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the 16 | // GNU General Public License for more details. 17 | // 18 | // You should have received a copy of the GNU General Public License 19 | // along with NeoGPS. If not, see . 20 | 21 | #ifdef __AVR__ 22 | 23 | #include 24 | 25 | #else 26 | 27 | #define PGM_P const char * 28 | 29 | #endif 30 | 31 | typedef PGM_P str_P; 32 | #define __PROGMEM PROGMEM 33 | 34 | #endif -------------------------------------------------------------------------------- /extras/configs/Full/GPSfix_cfg.h: -------------------------------------------------------------------------------- 1 | #ifndef GPS_FIX_CFG 2 | #define GPS_FIX_CFG 3 | 4 | /** 5 | * Enable/disable the storage for the members of a fix. 6 | * 7 | * Disabling a member prevents it from being parsed from a received message. 8 | * The disabled member cannot be accessed or stored, and its validity flag 9 | * would not be available. It will not be declared, and code that uses that 10 | * member will not compile. 11 | * 12 | * DATE and TIME are somewhat coupled in that they share a single `time_t`, 13 | * but they have separate validity flags. 14 | * 15 | * See also note regarding the DOP members, below. 16 | * 17 | */ 18 | 19 | #define GPS_FIX_DATE 20 | #define GPS_FIX_TIME 21 | #define GPS_FIX_LOCATION 22 | #define GPS_FIX_LOCATION_DMS 23 | #define GPS_FIX_ALTITUDE 24 | #define GPS_FIX_SPEED 25 | #define GPS_FIX_HEADING 26 | #define GPS_FIX_SATELLITES 27 | #define GPS_FIX_HDOP 28 | #define GPS_FIX_VDOP 29 | #define GPS_FIX_PDOP 30 | #define GPS_FIX_LAT_ERR 31 | #define GPS_FIX_LON_ERR 32 | #define GPS_FIX_ALT_ERR 33 | #define GPS_FIX_GEOID_HEIGHT 34 | 35 | #endif 36 | -------------------------------------------------------------------------------- /extras/configs/Nominal/GPSfix_cfg.h: -------------------------------------------------------------------------------- 1 | #ifndef GPS_FIX_CFG 2 | #define GPS_FIX_CFG 3 | 4 | /** 5 | * Enable/disable the storage for the members of a fix. 6 | * 7 | * Disabling a member prevents it from being parsed from a received message. 8 | * The disabled member cannot be accessed or stored, and its validity flag 9 | * would not be available. It will not be declared, and code that uses that 10 | * member will not compile. 11 | * 12 | * DATE and TIME are somewhat coupled in that they share a single `time_t`, 13 | * but they have separate validity flags. 14 | * 15 | * See also note regarding the DOP members, below. 16 | * 17 | */ 18 | 19 | #define GPS_FIX_DATE 20 | #define GPS_FIX_TIME 21 | #define GPS_FIX_LOCATION 22 | //#define GPS_FIX_LOCATION_DMS 23 | #define GPS_FIX_ALTITUDE 24 | #define GPS_FIX_SPEED 25 | #define GPS_FIX_HEADING 26 | #define GPS_FIX_SATELLITES 27 | //#define GPS_FIX_HDOP 28 | //#define GPS_FIX_VDOP 29 | //#define GPS_FIX_PDOP 30 | //#define GPS_FIX_LAT_ERR 31 | //#define GPS_FIX_LON_ERR 32 | //#define GPS_FIX_ALT_ERR 33 | //#define GPS_FIX_GEOID_HEIGHT 34 | 35 | #endif 36 | -------------------------------------------------------------------------------- /extras/configs/PUBX/GPSfix_cfg.h: -------------------------------------------------------------------------------- 1 | #ifndef GPS_FIX_CFG 2 | #define GPS_FIX_CFG 3 | 4 | /** 5 | * Enable/disable the storage for the members of a fix. 6 | * 7 | * Disabling a member prevents it from being parsed from a received message. 8 | * The disabled member cannot be accessed or stored, and its validity flag 9 | * would not be available. It will not be declared, and code that uses that 10 | * member will not compile. 11 | * 12 | * DATE and TIME are somewhat coupled in that they share a single `time_t`, 13 | * but they have separate validity flags. 14 | * 15 | * See also note regarding the DOP members, below. 16 | * 17 | */ 18 | 19 | #define GPS_FIX_DATE 20 | #define GPS_FIX_TIME 21 | #define GPS_FIX_LOCATION 22 | //#define GPS_FIX_LOCATION_DMS 23 | #define GPS_FIX_ALTITUDE 24 | #define GPS_FIX_SPEED 25 | #define GPS_FIX_HEADING 26 | #define GPS_FIX_SATELLITES 27 | //#define GPS_FIX_HDOP 28 | //#define GPS_FIX_VDOP 29 | //#define GPS_FIX_PDOP 30 | //#define GPS_FIX_LAT_ERR 31 | //#define GPS_FIX_LON_ERR 32 | //#define GPS_FIX_ALT_ERR 33 | //#define GPS_FIX_GEOID_HEIGHT 34 | 35 | #endif 36 | -------------------------------------------------------------------------------- /extras/configs/DTL/GPSfix_cfg.h: -------------------------------------------------------------------------------- 1 | #ifndef GPS_FIX_CFG 2 | #define GPS_FIX_CFG 3 | 4 | /** 5 | * Enable/disable the storage for the members of a fix. 6 | * 7 | * Disabling a member prevents it from being parsed from a received message. 8 | * The disabled member cannot be accessed or stored, and its validity flag 9 | * would not be available. It will not be declared, and code that uses that 10 | * member will not compile. 11 | * 12 | * DATE and TIME are somewhat coupled in that they share a single `time_t`, 13 | * but they have separate validity flags. 14 | * 15 | * See also note regarding the DOP members, below. 16 | * 17 | */ 18 | 19 | #define GPS_FIX_DATE 20 | #define GPS_FIX_TIME 21 | #define GPS_FIX_LOCATION 22 | //#define GPS_FIX_LOCATION_DMS 23 | //#define GPS_FIX_ALTITUDE 24 | //#define GPS_FIX_SPEED 25 | //#define GPS_FIX_HEADING 26 | //#define GPS_FIX_SATELLITES 27 | //#define GPS_FIX_HDOP 28 | //#define GPS_FIX_VDOP 29 | //#define GPS_FIX_PDOP 30 | //#define GPS_FIX_LAT_ERR 31 | //#define GPS_FIX_LON_ERR 32 | //#define GPS_FIX_ALT_ERR 33 | //#define GPS_FIX_GEOID_HEIGHT 34 | 35 | #endif 36 | -------------------------------------------------------------------------------- /extras/configs/Speed/GPSfix_cfg.h: -------------------------------------------------------------------------------- 1 | #ifndef GPS_FIX_CFG 2 | #define GPS_FIX_CFG 3 | 4 | /** 5 | * Enable/disable the storage for the members of a fix. 6 | * 7 | * Disabling a member prevents it from being parsed from a received message. 8 | * The disabled member cannot be accessed or stored, and its validity flag 9 | * would not be available. It will not be declared, and code that uses that 10 | * member will not compile. 11 | * 12 | * DATE and TIME are somewhat coupled in that they share a single `time_t`, 13 | * but they have separate validity flags. 14 | * 15 | * See also note regarding the DOP members, below. 16 | * 17 | */ 18 | 19 | //#define GPS_FIX_DATE 20 | //#define GPS_FIX_TIME 21 | //#define GPS_FIX_LOCATION 22 | //#define GPS_FIX_LOCATION_DMS 23 | //#define GPS_FIX_ALTITUDE 24 | #define GPS_FIX_SPEED 25 | //#define GPS_FIX_HEADING 26 | //#define GPS_FIX_SATELLITES 27 | //#define GPS_FIX_HDOP 28 | //#define GPS_FIX_VDOP 29 | //#define GPS_FIX_PDOP 30 | //#define GPS_FIX_LAT_ERR 31 | //#define GPS_FIX_LON_ERR 32 | //#define GPS_FIX_ALT_ERR 33 | //#define GPS_FIX_GEOID_HEIGHT 34 | 35 | #endif 36 | -------------------------------------------------------------------------------- /extras/configs/Minimal/GPSfix_cfg.h: -------------------------------------------------------------------------------- 1 | #ifndef GPS_FIX_CFG 2 | #define GPS_FIX_CFG 3 | 4 | /** 5 | * Enable/disable the storage for the members of a fix. 6 | * 7 | * Disabling a member prevents it from being parsed from a received message. 8 | * The disabled member cannot be accessed or stored, and its validity flag 9 | * would not be available. It will not be declared, and code that uses that 10 | * member will not compile. 11 | * 12 | * DATE and TIME are somewhat coupled in that they share a single `time_t`, 13 | * but they have separate validity flags. 14 | * 15 | * See also note regarding the DOP members, below. 16 | * 17 | */ 18 | 19 | //#define GPS_FIX_DATE 20 | //#define GPS_FIX_TIME 21 | //#define GPS_FIX_LOCATION 22 | //#define GPS_FIX_LOCATION_DMS 23 | //#define GPS_FIX_ALTITUDE 24 | //#define GPS_FIX_SPEED 25 | //#define GPS_FIX_HEADING 26 | //#define GPS_FIX_SATELLITES 27 | //#define GPS_FIX_HDOP 28 | //#define GPS_FIX_VDOP 29 | //#define GPS_FIX_PDOP 30 | //#define GPS_FIX_LAT_ERR 31 | //#define GPS_FIX_LON_ERR 32 | //#define GPS_FIX_ALT_ERR 33 | //#define GPS_FIX_GEOID_HEIGHT 34 | 35 | #endif 36 | -------------------------------------------------------------------------------- /extras/doc/Garmin.md: -------------------------------------------------------------------------------- 1 | # Garmin Proprietary messages 2 | 3 | To use the Garmin Proprietary NMEA message parser, you must enable the following in `NMEAGPS_cfg.h`: 4 | ``` 5 | #define NMEAGPS_PARSE_MFR_ID 6 | #define NMEAGPS_DERIVED_TYPES 7 | ``` 8 | 9 | **NeoGPS** implements the following additional NMEA messages: 10 | 11 | * $PGRMF - Fix data 12 | 13 | You may want to change the configured PGRM messages in `src/Garmin/PGRM_cfg.h`. It is currently configured to work with the example application, `PGRM.ino`. `PGRM_cfg.h` has the following configuration items: 14 | ``` 15 | #define GARMINGPS_PARSE_PGRMF 16 | ``` 17 | 18 | As shown in the PGRM.ino example program, you should use an instance of `GarminNMEA` instead of the typical `NMEAGPS`: 19 | 20 | ``` 21 | #include 22 | #include 23 | #include 24 | 25 | ... 26 | 27 | static GarminNMEA gps; // This parses received characters 28 | static gps_fix fix; 29 | ``` 30 | 31 | A few different header files are included, but all other operations are identical. 32 | 33 | Notice that the $PGRMF message sets the global variable, `GPSTime::leap_seconds`. As reported in 34 | [Issue #90](https://github.com/SlashDevin/NeoGPS/issues/90), this is required for exact UTC 35 | calculations that span dates with different GPS leap seconds 36 | (see [Wikipedia article](http://en.wikipedia.org/wiki/Global_Positioning_System#Leap_seconds)). -------------------------------------------------------------------------------- /extras/doc/Coherency.md: -------------------------------------------------------------------------------- 1 | Coherency 2 | ========== 3 | Coherency guarantees that all members of a fix are from the same GPS time. For example, lat/long members may have been set by the newest sentence, but the altitude may be from the previous time interval. Most applications do not care that the fix members are not coherent. However, if you are controlling a drone or other autonomous vehicle, you may need coherency. 4 | 5 | NeoGPS achieves coherency by detecting the "quiet" time between batches of sentences. When new data starts coming in, the fix will get emptied or initialized, and all new sentences will be accumulated in the internal fix. 6 | 7 | If coherency is desired, **you must choose the correct LAST_SENTENCE_IN_INTERVAL.** If you're not sure which sentence is sent last (and therefore, when the quiet time begins), use NMEAorder.ino to analyze your GPS device. 8 | 9 | You must also use **EXPLICIT_MERGING**. Implicit merging cannot be used with coherency is because a sentence has to be parsed to know its timestamp. If it were implicitly merged, the old data would not have been invalidated. Invalidating data from a previous update period must be performed _before_ the sentence parsing begins. That can only be accomplished with a second 'safe' copy of the fix data and explicit merging (i.e., FIX_MAX >= 1). With implicit merging, new data has already been mixed with old data by the time DECODE_COMPLETED occurs and timestamps can be checked. 10 | 11 | When you have correctly chosen the LAST_SENTENCE_IN_INTERVAL *and* EXPLICIT_MERGING, the fix-oriented methods `available` and `read()` will return a coherent fix. 12 | 13 | NOTE: If you use the [character-oriented methods](CharOriented.md) `decode`, `is_safe` and `fix()` to handle individual sentences, you must check `intervalComplete()` to know when the GPS update interval is completed, and the GPS quiet time has started. 14 | -------------------------------------------------------------------------------- /extras/doc/RAM.md: -------------------------------------------------------------------------------- 1 | RAM requirements 2 | ======= 3 | 4 | #### **NeoGPS** requires **72% to 96% _less_ RAM, saving 140 to 1100 bytes.** 5 | 6 | Because you can select what data members are stored, the RAM savings depends on the [configuration](Configurations.md): 7 | 8 | 9 | 10 | 11 | 12 | 13 | 14 |
ConfigurationNeoGPS
Size
TinyGPS
Size (% smaller)
TinyGPS++
Size (% smaller)
Adafruit_GPS
Size (% smaller)
Minimal10- (95%)- (96%)
DTL25- (86%)- (90%)
Nominal41180 (72%)240 (83%)326 (87%)
Full242- (-)~1400 (83%)
15 | 16 | #### Why does **NeoGPS** use less RAM? 17 | 18 | As data is received from the device, various portions of a `fix` are 19 | modified. In fact, _**no buffering RAM is required**_. Each character 20 | affects the internal state machine and may also contribute to a data member 21 | (e.g., latitude). 22 | 23 | If your application only requires an accurate one pulse-per-second, you 24 | can configure it to parse *no* sentence types and retain *no* data members. 25 | This is the **Minimal** configuration. Although the 26 | `fix().status` can be checked, no valid flags are available. Even 27 | though no sentences are parsed and no data members are stored, the 28 | application will still receive an empty `fix` once per second: 29 | 30 | ``` 31 | while (gps.available( gpsPort )) { 32 | gps_fix nothingButStatus = gps.read(); 33 | sentenceReceived(); 34 | } 35 | ``` 36 | 37 | The `ubloxNMEA` derived class doesn't use any extra bytes of RAM. 38 | 39 | The `ubloxGPS` derived class adds 20 bytes to handle the more-complicated protocol, 40 | plus 5 static bytes for converting GPS time and Time Of Week to UTC. 41 | 42 | -------------------------------------------------------------------------------- /src/GPSfix_cfg.h: -------------------------------------------------------------------------------- 1 | #ifndef GPS_FIX_CFG 2 | #define GPS_FIX_CFG 3 | 4 | // Copyright (C) 2014-2017, SlashDevin 5 | // 6 | // This file is part of NeoGPS 7 | // 8 | // NeoGPS is free software: you can redistribute it and/or modify 9 | // it under the terms of the GNU General Public License as published by 10 | // the Free Software Foundation, either version 3 of the License, or 11 | // (at your option) any later version. 12 | // 13 | // NeoGPS is distributed in the hope that it will be useful, 14 | // but WITHOUT ANY WARRANTY; without even the implied warranty of 15 | // MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the 16 | // GNU General Public License for more details. 17 | // 18 | // You should have received a copy of the GNU General Public License 19 | // along with NeoGPS. If not, see . 20 | 21 | /** 22 | * Enable/disable the storage for the members of a fix. 23 | * 24 | * Disabling a member prevents it from being parsed from a received message. 25 | * The disabled member cannot be accessed or stored, and its validity flag 26 | * would not be available. It will not be declared, and code that uses that 27 | * member will not compile. 28 | * 29 | * DATE and TIME are somewhat coupled in that they share a single `time_t`, 30 | * but they have separate validity flags. 31 | * 32 | * See also note regarding the DOP members, below. 33 | * 34 | */ 35 | 36 | #define GPS_FIX_DATE 37 | #define GPS_FIX_TIME 38 | #define GPS_FIX_LOCATION 39 | //#define GPS_FIX_LOCATION_DMS 40 | #define GPS_FIX_ALTITUDE 41 | #define GPS_FIX_SPEED 42 | //#define GPS_FIX_VELNED 43 | #define GPS_FIX_HEADING 44 | #define GPS_FIX_SATELLITES 45 | //#define GPS_FIX_HDOP 46 | //#define GPS_FIX_VDOP 47 | //#define GPS_FIX_PDOP 48 | //#define GPS_FIX_LAT_ERR 49 | //#define GPS_FIX_LON_ERR 50 | //#define GPS_FIX_ALT_ERR 51 | //#define GPS_FIX_SPD_ERR 52 | //#define GPS_FIX_HDG_ERR 53 | //#define GPS_FIX_TIME_ERR 54 | //#define GPS_FIX_GEOID_HEIGHT 55 | 56 | #endif 57 | -------------------------------------------------------------------------------- /src/Streamers.h: -------------------------------------------------------------------------------- 1 | #ifndef STREAMERS_H 2 | #define STREAMERS_H 3 | 4 | // Copyright (C) 2014-2017, SlashDevin 5 | // 6 | // This file is part of NeoGPS 7 | // 8 | // NeoGPS is free software: you can redistribute it and/or modify 9 | // it under the terms of the GNU General Public License as published by 10 | // the Free Software Foundation, either version 3 of the License, or 11 | // (at your option) any later version. 12 | // 13 | // NeoGPS is distributed in the hope that it will be useful, 14 | // but WITHOUT ANY WARRANTY; without even the implied warranty of 15 | // MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the 16 | // GNU General Public License for more details. 17 | // 18 | // You should have received a copy of the GNU General Public License 19 | // along with NeoGPS. If not, see . 20 | 21 | #include 22 | 23 | extern Print & operator <<( Print & outs, const bool b ); 24 | extern Print & operator <<( Print & outs, const char c ); 25 | extern Print & operator <<( Print & outs, const uint16_t v ); 26 | extern Print & operator <<( Print & outs, const uint32_t v ); 27 | extern Print & operator <<( Print & outs, const int32_t v ); 28 | extern Print & operator <<( Print & outs, const uint8_t v ); 29 | extern Print & operator <<( Print & outs, const __FlashStringHelper *s ); 30 | 31 | class gps_fix; 32 | 33 | /** 34 | * Print valid fix data to the given stream with the format 35 | * "status,dateTime,lat,lon,heading,speed,altitude,satellites, 36 | * hdop,vdop,pdop,lat_err,lon_err,alt_err" 37 | * The "header" above contains the actual compile-time configuration. 38 | * A comma-separated field will be empty if the data is NOT valid. 39 | * @param[in] outs output stream. 40 | * @param[in] fix gps_fix instance. 41 | * @return iostream. 42 | */ 43 | extern Print & operator <<( Print &outs, const gps_fix &fix ); 44 | 45 | class NMEAGPS; 46 | 47 | extern void trace_header( Print & outs ); 48 | extern void trace_all( Print & outs, const NMEAGPS &gps, const gps_fix &fix ); 49 | 50 | #endif -------------------------------------------------------------------------------- /src/DMS.h: -------------------------------------------------------------------------------- 1 | #ifndef DMS_H 2 | #define DMS_H 3 | 4 | // Copyright (C) 2014-2017, SlashDevin 5 | // 6 | // This file is part of NeoGPS 7 | // 8 | // NeoGPS is free software: you can redistribute it and/or modify 9 | // it under the terms of the GNU General Public License as published by 10 | // the Free Software Foundation, either version 3 of the License, or 11 | // (at your option) any later version. 12 | // 13 | // NeoGPS is distributed in the hope that it will be useful, 14 | // but WITHOUT ANY WARRANTY; without even the implied warranty of 15 | // MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the 16 | // GNU General Public License for more details. 17 | // 18 | // You should have received a copy of the GNU General Public License 19 | // along with NeoGPS. If not, see . 20 | 21 | #include "NeoGPS_cfg.h" 22 | #include 23 | class Print; 24 | 25 | enum Hemisphere_t { NORTH_H = 0, SOUTH_H = 1, EAST_H = 0, WEST_H = 1 }; 26 | 27 | class DMS_t 28 | { 29 | public: 30 | uint8_t degrees; 31 | uint8_t minutes ;//NEOGPS_BF(6); 32 | Hemisphere_t hemisphere ;//NEOGPS_BF(2); compiler bug! 33 | uint8_t seconds_whole NEOGPS_BF(6); 34 | uint16_t seconds_frac NEOGPS_BF(10); // 1000ths 35 | 36 | void init() { degrees = minutes = seconds_whole = seconds_frac = 0; 37 | hemisphere = NORTH_H; } 38 | 39 | float secondsF() const { return seconds_whole + 0.001 * seconds_frac; }; 40 | char NS () const { return (hemisphere == SOUTH_H) ? 'S' : 'N'; }; 41 | char EW () const { return (hemisphere == WEST_H) ? 'W' : 'E'; }; 42 | 43 | //............................................................................. 44 | // A utility function to convert from integer 'lat' or 'lon', scaled by 10^7 45 | 46 | void From( int32_t deg_1E7 ); 47 | 48 | // Print DMS as the funky NMEA DDDMM.mmmm format 49 | void printDDDMMmmmm( Print & outs ) const; 50 | 51 | } NEOGPS_PACKED; 52 | 53 | extern Print & operator << ( Print & outs, const DMS_t & ); 54 | 55 | #endif -------------------------------------------------------------------------------- /examples/NMEAblink/NMEAblink.ino: -------------------------------------------------------------------------------- 1 | #include 2 | 3 | //====================================================================== 4 | // Program: NMEAblink.ino 5 | // 6 | // Prerequisites: 7 | // 1) NMEA.ino works with your device 8 | // 9 | // Description: This program will toggle the LED once per second, 10 | // when the LAST_SENTENCE_IN_INTERVAL is received. 11 | // 12 | // Because no actual GPS data is used, you could disable all 13 | // messages (except the LAST_SENTENCE) and all gps_fix members. 14 | // It would still receive a 'fix' oncer per second, without 15 | // without using any RAM or CPU time to parse or save 16 | // the (unused) values. Essentially, this app uses the LAST_SENTENCE 17 | // as a 1PPS signal. 18 | // 19 | // Note: Because this example does not use 'Serial', you 20 | // could use 'Serial' for the gpsPort, like this: 21 | // 22 | // #define gpsPort Serial 23 | // 24 | // See GPSport.h for more information. 25 | // 26 | // License: 27 | // Copyright (C) 2014-2017, SlashDevin 28 | // 29 | // This file is part of NeoGPS 30 | // 31 | // NeoGPS is free software: you can redistribute it and/or modify 32 | // it under the terms of the GNU General Public License as published by 33 | // the Free Software Foundation, either version 3 of the License, or 34 | // (at your option) any later version. 35 | // 36 | // NeoGPS is distributed in the hope that it will be useful, 37 | // but WITHOUT ANY WARRANTY; without even the implied warranty of 38 | // MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the 39 | // GNU General Public License for more details. 40 | // 41 | // You should have received a copy of the GNU General Public License 42 | // along with NeoGPS. If not, see . 43 | // 44 | //====================================================================== 45 | 46 | #include 47 | 48 | static NMEAGPS gps; 49 | static const int led = 13; 50 | 51 | //-------------------------- 52 | 53 | void setup() 54 | { 55 | gpsPort.begin(9600); 56 | 57 | pinMode(led, OUTPUT); 58 | } 59 | 60 | //-------------------------- 61 | 62 | void loop() 63 | { 64 | if (gps.available( gpsPort)) { 65 | gps.read(); // don't really do anything with the fix... 66 | 67 | digitalWrite( led, !digitalRead(led) ); // toggle the LED 68 | } 69 | } 70 | -------------------------------------------------------------------------------- /examples/NMEAsimple/NMEAsimple.ino: -------------------------------------------------------------------------------- 1 | #include 2 | 3 | //====================================================================== 4 | // Program: NMEAsimple.ino 5 | // 6 | // Description: This program shows simple usage of NeoGPS 7 | // 8 | // Prerequisites: 9 | // 1) NMEA.ino works with your device (correct TX/RX pins and baud rate) 10 | // 2) At least one of the RMC, GGA or GLL sentences have been enabled in NMEAGPS_cfg.h. 11 | // 3) Your device at least one of those sentences (use NMEAorder.ino to confirm). 12 | // 4) LAST_SENTENCE_IN_INTERVAL has been set to one of those sentences in NMEAGPS_cfg.h (use NMEAorder.ino). 13 | // 5) LOCATION and ALTITUDE have been enabled in GPSfix_cfg.h 14 | // 15 | // 'Serial' is for debug output to the Serial Monitor window. 16 | // 17 | // License: 18 | // Copyright (C) 2014-2017, SlashDevin 19 | // 20 | // This file is part of NeoGPS 21 | // 22 | // NeoGPS is free software: you can redistribute it and/or modify 23 | // it under the terms of the GNU General Public License as published by 24 | // the Free Software Foundation, either version 3 of the License, or 25 | // (at your option) any later version. 26 | // 27 | // NeoGPS is distributed in the hope that it will be useful, 28 | // but WITHOUT ANY WARRANTY; without even the implied warranty of 29 | // MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the 30 | // GNU General Public License for more details. 31 | // 32 | // You should have received a copy of the GNU General Public License 33 | // along with NeoGPS. If not, see . 34 | // 35 | //====================================================================== 36 | 37 | #include 38 | 39 | NMEAGPS gps; // This parses the GPS characters 40 | gps_fix fix; // This holds on to the latest values 41 | 42 | void setup() 43 | { 44 | DEBUG_PORT.begin(9600); 45 | while (!Serial) 46 | ; 47 | DEBUG_PORT.print( F("NMEAsimple.INO: started\n") ); 48 | 49 | gpsPort.begin(9600); 50 | } 51 | 52 | //-------------------------- 53 | 54 | void loop() 55 | { 56 | while (gps.available( gpsPort )) { 57 | fix = gps.read(); 58 | 59 | DEBUG_PORT.print( F("Location: ") ); 60 | if (fix.valid.location) { 61 | DEBUG_PORT.print( fix.latitude(), 6 ); 62 | DEBUG_PORT.print( ',' ); 63 | DEBUG_PORT.print( fix.longitude(), 6 ); 64 | } 65 | 66 | DEBUG_PORT.print( F(", Altitude: ") ); 67 | if (fix.valid.altitude) 68 | DEBUG_PORT.print( fix.altitude() ); 69 | 70 | DEBUG_PORT.println(); 71 | } 72 | } 73 | -------------------------------------------------------------------------------- /extras/doc/CharOriented.md: -------------------------------------------------------------------------------- 1 | Character-oriented methods 2 | =========================== 3 | 4 | Sometimes, individual characters or sentences must be processed or filtered, long before a fix structure is completed (i.e., `available()`). In this advanced technique, your sketch should read each character and pass it to the character-oriented method `gps.decode()`: 5 | ``` 6 | void loop() 7 | { 8 | while (serial.available()) { 9 | char c = serial.read(); 10 | if (gps.decode( c ) == DECODE_COMPLETED) { 11 | ... do something with gps.fix()... 12 | } 13 | ``` 14 | As `gps` decodes those bytes, it will gradually fill out the pieces of its internal fix structure, `gps.fix()` (members described [here](Data%20Model.md). When you want to use some of the fix data, you can access it like this: 15 | ``` 16 | Serial.print( gps.fix().latitude() ); 17 | Serial.print( ',' ); 18 | Serial.println( gps.fix().longitude() ); 19 | ``` 20 | However, you must wait for the sentence to be completely decoded. You can't access `gps.fix()` unless you know that it is COMPLETED. You must copy it to another fix variable if you need to access it at any time. 21 | 22 | **IMPORTANT:** `gps.fix()` **IS ONLY VALID WHEN:** 23 | - `gps.decode()` just returned `DECODE_COMPLETED`, or 24 | - `gps.is_safe()` 25 | 26 | This is because `gps.fix().speed` may be half-formed. You must either do all your accessing immediately after `gps.decode()` returns `DECODE_COMPLETED`: 27 | ``` 28 | void loop() 29 | { 30 | // At this point of the code, speed could be half-decoded. 31 | if (gps.fix().speed <= 5) // NOT A GOOD IDEA! 32 | Serial.println( F("Too slow!") ); 33 | 34 | while (serial.available()) { 35 | char c = serial.read(); 36 | if (gps.decode( serial.read() ) == NMEAGPS::DECODE_COMPLETED) { 37 | 38 | // Access any piece of gps.fix() in here... 39 | 40 | if (gps.fix().speed <= 5) // OK! 41 | Serial.println( F("Too slow!") ); 42 | 43 | if (gps.fix().lat ... 44 | } 45 | } 46 | 47 | ``` 48 | Or you must call `gps.is_safe()` before using `gps.fix()`. It is safest to copy `gps.fix()` into your own variable for use at any time: 49 | ``` 50 | gps_fix my_fix; 51 | 52 | void loop() 53 | { 54 | while (serial.available()) { 55 | char c = serial.read(); 56 | if (gps.decode( serial.read() ) == NMEAGPS::DECODE_COMPLETED) { 57 | my_fix = gps.fix(); // save for later... 58 | } 59 | } 60 | 61 | if (my_fix.speed <= 5) // OK 62 | DigitalWrite( UNDERSPEED_INDICATOR, HIGH ); 63 | ``` 64 | Although the character-oriented program structure gives you a finer granularity of control, you must be more careful when accessing `gps.fix()`. 65 | -------------------------------------------------------------------------------- /examples/NMEA_isr/NMEA_isr.ino: -------------------------------------------------------------------------------- 1 | #include 2 | 3 | //====================================================================== 4 | // Program: NMEA_isr.ino 5 | // 6 | // Prerequisites: 7 | // 1) NMEA.ino works with your device 8 | // 9 | // Description: This minimal program parses the GPS data during the 10 | // RX character interrupt. The ISR passes the character to 11 | // the GPS object for parsing. The GPS object will add gps_fix 12 | // structures to a buffer that can be later read() by loop(). 13 | // 14 | // License: 15 | // Copyright (C) 2014-2017, SlashDevin 16 | // 17 | // This file is part of NeoGPS 18 | // 19 | // NeoGPS is free software: you can redistribute it and/or modify 20 | // it under the terms of the GNU General Public License as published by 21 | // the Free Software Foundation, either version 3 of the License, or 22 | // (at your option) any later version. 23 | // 24 | // NeoGPS is distributed in the hope that it will be useful, 25 | // but WITHOUT ANY WARRANTY; without even the implied warranty of 26 | // MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the 27 | // GNU General Public License for more details. 28 | // 29 | // You should have received a copy of the GNU General Public License 30 | // along with NeoGPS. If not, see . 31 | // 32 | //====================================================================== 33 | 34 | #include 35 | 36 | #include 37 | 38 | // Check configuration 39 | 40 | #ifndef NMEAGPS_INTERRUPT_PROCESSING 41 | #error You must define NMEAGPS_INTERRUPT_PROCESSING in NMEAGPS_cfg.h! 42 | #endif 43 | 44 | static NMEAGPS gps; 45 | 46 | //-------------------------- 47 | 48 | static void GPSisr( uint8_t c ) 49 | { 50 | gps.handle( c ); 51 | 52 | } // GPSisr 53 | 54 | //-------------------------- 55 | 56 | void setup() 57 | { 58 | DEBUG_PORT.begin(9600); 59 | while (!DEBUG_PORT) 60 | ; 61 | 62 | DEBUG_PORT.print( F("NMEA_isr.INO: started\n") ); 63 | DEBUG_PORT.print( F("fix object size = ") ); 64 | DEBUG_PORT.println( sizeof(gps.fix()) ); 65 | DEBUG_PORT.print( F("NMEAGPS object size = ") ); 66 | DEBUG_PORT.println( sizeof(gps) ); 67 | DEBUG_PORT.println( F("Looking for GPS device on " GPS_PORT_NAME) ); 68 | 69 | trace_header( DEBUG_PORT ); 70 | 71 | DEBUG_PORT.flush(); 72 | 73 | gpsPort.attachInterrupt( GPSisr ); 74 | gpsPort.begin( 9600 ); 75 | } 76 | 77 | //-------------------------- 78 | 79 | void loop() 80 | { 81 | if (gps.available()) { 82 | // Print all the things! 83 | trace_all( DEBUG_PORT, gps, gps.read() ); 84 | } 85 | 86 | if (gps.overrun()) { 87 | gps.overrun( false ); 88 | DEBUG_PORT.println( F("DATA OVERRUN: took too long to print GPS data!") ); 89 | } 90 | } 91 | -------------------------------------------------------------------------------- /extras/doc/Tradeoffs.md: -------------------------------------------------------------------------------- 1 | Tradeoffs 2 | ========= 3 | 4 | There's a price for everything, hehe... 5 | 6 | #### Configurability means that the code is littered with #ifdef sections. 7 | 8 | I've tried to increase white space and organization to make it more readable, but let's be honest... 9 | conditional compilation is ugly. 10 | 11 | #### Accumulating parts means knowing which parts are valid. 12 | 13 | Before accessing a part, you must check its `valid` flag. Fortunately, this adds only one bit per member. See [Streamers.cpp](/src/Streamers.cpp#L100) for an example of accessing every data member. That file also shows how to accommodate different builds: all references to 'gps_fix' members are wrapped with conditional compilation `#ifdef`/`#endif` statements. If you do not plan to support multiple configurations, you do not need to use `#ifdef`/`#endif` statements. 14 | 15 | #### Parsing without buffers, or *in place*, means that you must be more careful about when you access data items. 16 | 17 | In general, using the fix-oriented methods `available` and `read` are atomically safe. You can access any parts of your `fix` structure, at any time. 18 | 19 | If you are using the advanced [character-oriented methods](/extras/doc/CharOriented.md): 20 | 21 | * You must wait to access the internal `gps.fix()` until after the entire sentence has been parsed. 22 | * Only 3 example programs use these methods: NMEAblink, NMEAorder and NMEAdiagnostic. These examples simply `decode` until a sentence is COMPLETED. See `GPSloop()` in [NMEAdiagnostic.ino](/examples/NMEAdiagnostoc/NMEAdiagnostic.ino). 23 | * Member function `gps.is_safe()` can also be used to determine when it is safe to access the internal `gps.fix()`. 24 | * Received data errors can cause invalid field values to be set in the internal fix *before* the CRC is fully computed. The CRC will 25 | catch most of those, and the internal fix members will then be marked as invalid. 26 | 27 | #### Accumulating parts into *one* fix means less RAM but more complicated code 28 | 29 | By enabling one of the [merging](/extras/doc/Merging.md) methods, fixes will accumulate data from all received sentences. The code required to implement those different techniques is more complicated than simply setting a structure member. 30 | 31 | You are not restricted from having other instances of fix; you can copy or merge a some or all of a new fix into another copy if you want. 32 | 33 | #### Full C++ OO implementation is more advanced than most Arduino libraries. 34 | 35 | You've been warned! ;) 36 | 37 | #### "fast, good, cheap... pick two." 38 | 39 | Although most of the RAM reduction is due to eliminating buffers, some of it is from trading RAM 40 | for additional code (see **Nominal** Program Space above). And, as I mentioned, the readabilty (i.e., goodness) suffers from its configurability. 41 | -------------------------------------------------------------------------------- /extras/doc/Performance.md: -------------------------------------------------------------------------------- 1 | Performance 2 | =========== 3 | 4 | #### **NeoGPS** is **40% to 70% faster**. 5 | 6 | For comparison, the following sentences were parsed by various [Configurations](/doc/Configurations.md) of **NeoGPS**, **TinyGPS** and **TinyGPSPlus** on a 16MHz Arduino Mega2560. 7 | 8 | ``` 9 | $GPGGA,092725.00,4717.11399,N,00833.91590,E,1,8,1.01,499.6,M,48.0,M,,0*5B 10 | $GPRMC,083559.00,A,4717.11437,N,00833.91522,E,0.004,77.52,091202,,,A*57 11 | $GPGSV,3,1,10,23,38,230,44,29,71,156,47,07,29,116,41,08,09,081,36*7F 12 | $GPGSV,3,2,10,10,07,189,,05,05,220,,09,34,274,42,18,25,309,44*72 13 | $GPGSV,3,3,10,26,82,187,47,28,43,056,46*77 14 | ``` 15 | 16 | 17 | 18 | 19 | 20 | 21 | 22 |
ConfigurationSentenceNeoGPSTinyGPS
Time (% faster)
TinyGPS++
Time (% faster)
Adafrut_GPS
Time (%faster)
MinimalGGA
RMC
329us
335us
- (78%)
- (77%)
- (78%)
- (77%)
DTLGGA
RMC
780us
803us
- (46%)
- (44%)
- (47%)
- (44%)
NominalGGA
RMC
864us
883us
1448us (40%)
1435us (39%)
1473us (41%)
1442us (39%)
1358us (36%)
1535us (42%)
FullGGA
RMC
GSV
908us
899us
2194us
- (37%)
- (37%)
- (-)
1523us (40%)
1560us (42%)
6651us (67%)
23 | 24 | #### Why is **NeoGPS** faster? 25 | 26 | Most libraries use extra buffers to accumulate parts of the sentence so they 27 | can be parsed all at once. For example, an extra field buffer may hold on 28 | to all the characters between commas. That buffer is then parsed into a 29 | single data item, like `heading`. Some libraries even hold on to the 30 | *entire* sentence before attempting to parse it. In addition to increasing 31 | the RAM requirements, this requires **extra CPU time** to copy the bytes and 32 | index through them... again. 33 | 34 | **NeoGPS** parses each character immediately into the data item. When the 35 | delimiting comma is received, the data item has been fully computed *in 36 | place* and is marked as valid. 37 | 38 | Most libraries parse all fields of their selected sentences. Although most 39 | people use GPS for obtaining lat/long, some need only time, or even just one 40 | pulse-per-second. 41 | 42 | **NeoGPS** configures each item separately. Disabled items are 43 | conditionally compiled, which means they will not use any RAM, program space 44 | or CPU time. The characters from those fields are simply skipped; they are 45 | never copied into a buffer or processed. 46 | 47 | While it is significantly faster and smaller than all NMEA parsers, these same improvements also make 48 | NeoGPS faster and smaller than _binary_ parsers. 49 | -------------------------------------------------------------------------------- /src/ublox/ubxmsg.cpp: -------------------------------------------------------------------------------- 1 | // Copyright (C) 2014-2017, SlashDevin 2 | // 3 | // This file is part of NeoGPS 4 | // 5 | // NeoGPS is free software: you can redistribute it and/or modify 6 | // it under the terms of the GNU General Public License as published by 7 | // the Free Software Foundation, either version 3 of the License, or 8 | // (at your option) any later version. 9 | // 10 | // NeoGPS is distributed in the hope that it will be useful, 11 | // but WITHOUT ANY WARRANTY; without even the implied warranty of 12 | // MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the 13 | // GNU General Public License for more details. 14 | // 15 | // You should have received a copy of the GNU General Public License 16 | // along with NeoGPS. If not, see . 17 | 18 | #include "ublox/ubxGPS.h" 19 | 20 | // Disable the entire file if derived types are not allowed. 21 | #ifdef NMEAGPS_DERIVED_TYPES 22 | 23 | #if !defined(UBLOX_PARSE_STATUS) & !defined(UBLOX_PARSE_TIMEGPS) & \ 24 | !defined(UBLOX_PARSE_TIMEUTC) & !defined(UBLOX_PARSE_POSLLH) & \ 25 | !defined(UBLOX_PARSE_DOP) & !defined(UBLOX_PARSE_PVT) & \ 26 | !defined(UBLOX_PARSE_VELNED) & !defined(UBLOX_PARSE_SVINFO) & \ 27 | !defined(UBLOX_PARSE_HNR_PVT) 28 | 29 | // No UBX binary messages defined, ignore rest of file 30 | 31 | #else 32 | 33 | using namespace ublox; 34 | 35 | bool ublox::configNMEA( ubloxGPS &gps, NMEAGPS::nmea_msg_t msgType, uint8_t rate ) 36 | { 37 | static const ubx_nmea_msg_t ubx[] __PROGMEM = { 38 | #if defined(NMEAGPS_PARSE_GGA) | defined(NMEAGPS_RECOGNIZE_ALL) 39 | UBX_GPGGA, 40 | #endif 41 | 42 | #if defined(NMEAGPS_PARSE_GLL) | defined(NMEAGPS_RECOGNIZE_ALL) 43 | UBX_GPGLL, 44 | #endif 45 | 46 | #if defined(NMEAGPS_PARSE_GSA) | defined(NMEAGPS_RECOGNIZE_ALL) 47 | UBX_GPGSA, 48 | #endif 49 | 50 | #if defined(NMEAGPS_PARSE_GST) | defined(NMEAGPS_RECOGNIZE_ALL) 51 | UBX_GPGST, 52 | #endif 53 | 54 | #if defined(NMEAGPS_PARSE_GSV) | defined(NMEAGPS_RECOGNIZE_ALL) 55 | UBX_GPGSV, 56 | #endif 57 | 58 | #if defined(NMEAGPS_PARSE_RMC) | defined(NMEAGPS_RECOGNIZE_ALL) 59 | UBX_GPRMC, 60 | #endif 61 | 62 | #if defined(NMEAGPS_PARSE_VTG) | defined(NMEAGPS_RECOGNIZE_ALL) 63 | UBX_GPVTG, 64 | #endif 65 | 66 | #if defined(NMEAGPS_PARSE_ZDA) | defined(NMEAGPS_RECOGNIZE_ALL) 67 | UBX_GPZDA, 68 | #endif 69 | }; 70 | 71 | uint8_t msg_index = (uint8_t) msgType - (uint8_t) NMEAGPS::NMEA_FIRST_MSG; 72 | 73 | if (msg_index >= sizeof(ubx)/sizeof(ubx[0])) 74 | return false; 75 | 76 | msg_id_t msg_id = (msg_id_t) pgm_read_byte( &ubx[msg_index] ); 77 | 78 | return gps.send( cfg_msg_t( UBX_NMEA, msg_id, rate ) ); 79 | } 80 | 81 | #endif // UBX messages defined 82 | 83 | #endif // NMEAGPS_DERIVED_TYPES -------------------------------------------------------------------------------- /extras/doc/Extending.md: -------------------------------------------------------------------------------- 1 | Extending NeoGPS 2 | ========= 3 | Using features that are unique to your device fall into three categories: 4 | 5 | #### 1. Configuring the device with special commands 6 | Many devices allow you to configure which standard messages are emitted, or the rate at which they are emitted. It may be as simple as sending a proprietary command to the device. Simply use the NMEAGPS `send` or `send_P` method. 7 | 8 | For example, to set the baudrate of the ublox NEO-6M gps device, send it a 9 | `UBX,41` message: 10 | ``` 11 | gps.send_P( F("PUBX,41,1,0007,0003,19200,0") ); 12 | ``` 13 | 14 | #### 2. Parsing additional message types 15 | Some devices provide additional messages with extra information, or more efficient groupings. This will require deriving a class from `NMEAGPS`. The derived class needs to 16 | * declare a PROGMEM table of the new message types, 17 | * point that table back to the NMEAGPS table 18 | * override the `parseField` method to extract information from each new message type 19 | 20 | Please see ubxNMEA.h and .cpp for an example of adding two ublox-proprietary messages. 21 | 22 | #### 3. Handling new protocols 23 | Some devices provide additional protocols. They are frequently binary, which requires 24 | fewer bytes than NMEA 0183. Because they can both be transmitted on the same port, it is 25 | very likely that they can be distinguished at the message framing level. 26 | 27 | For example, NMEA messages always start with a '$' and end with CR/LF. ublox messages start 28 | with 0xB5 and 0x62 bytes, a message class and id, and a 2-byte message length. There is no 29 | terminating character; the message completed when `length` bytes have been received. 30 | 31 | This will require deriving a class from `NMEAGPS`. The derived class needs 32 | to 33 | * define new `rxState` values for the protocol state machine. These should 34 | be unique from the NMEA state values, but they should share the IDLE state 35 | value. 36 | * override the `decode` method to watch for its messages. As bytes are 37 | received, it may transition out of the IDLE state and into its own set of 38 | state values. If the character is not valid for this protocol, it should 39 | delegate it to the NMEAGPS base clase, which may begin processing an NMEAGPS 40 | message. If the rxState is not one of the derived states (i.e., it is in 41 | one of the NMEAGPS states), the character should be delegated to 42 | NMEAGPS::decode. 43 | * implement something like the `parseField` method if parse-in-place 44 | behavior is desirable. This is not necessarily `virtual`, as it will only 45 | be called from the derived `decode`. 46 | * You are free to add methods and data members as required for handling the 47 | protocol. Only `decode` must be overridden. 48 | 49 | Please see ubxGPS.h and .cpp for an example of implementing the 50 | ublox-proprietary protocol, UBX. The derived `ubloxGPS` class provides both 51 | parse-in-place *and* buffered messages. See the `send` and `poll` methods. 52 | 53 | -------------------------------------------------------------------------------- /examples/NMEAdistance/NMEAdistance.ino: -------------------------------------------------------------------------------- 1 | #include 2 | 3 | //====================================================================== 4 | // Program: NMEAdistance.ino 5 | // 6 | // Description: Display distance from a base location. 7 | // 8 | // Prerequisites: 9 | // 1) NMEA.ino works with your device (correct TX/RX pins and baud rate) 10 | // 2) GPS_FIX_LOCATION has been enabled. 11 | // 3) A sentence that contains lat/long has been enabled (GGA, GLL or RMC). 12 | // 4) Your device sends at least one of those sentences. 13 | // 14 | // 'Serial' is for debug output to the Serial Monitor window. 15 | // 16 | // License: 17 | // Copyright (C) 2014-2017, SlashDevin 18 | // 19 | // This file is part of NeoGPS 20 | // 21 | // NeoGPS is free software: you can redistribute it and/or modify 22 | // it under the terms of the GNU General Public License as published by 23 | // the Free Software Foundation, either version 3 of the License, or 24 | // (at your option) any later version. 25 | // 26 | // NeoGPS is distributed in the hope that it will be useful, 27 | // but WITHOUT ANY WARRANTY; without even the implied warranty of 28 | // MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the 29 | // GNU General Public License for more details. 30 | // 31 | // You should have received a copy of the GNU General Public License 32 | // along with NeoGPS. If not, see . 33 | // 34 | //====================================================================== 35 | 36 | #include 37 | 38 | //------------------------------------------------------------ 39 | // Check that the config files are set up properly 40 | 41 | #if !defined( NMEAGPS_PARSE_RMC ) & \ 42 | !defined( NMEAGPS_PARSE_GGA ) & \ 43 | !defined( NMEAGPS_PARSE_GLL ) 44 | #error You must uncomment at least one of NMEAGPS_PARSE_RMC, NMEAGPS_PARSE_GGA or NMEAGPS_PARSE_GLL in NMEAGPS_cfg.h! 45 | #endif 46 | 47 | #if !defined( GPS_FIX_LOCATION ) 48 | #error You must uncomment GPS_FIX_LOCATION in GPSfix_cfg.h! 49 | #endif 50 | 51 | NMEAGPS gps; 52 | 53 | // The base location, in degrees * 10,000,000 54 | NeoGPS::Location_t base( -253448688L, 1310324914L ); // Ayers Rock, AU 55 | 56 | void setup() 57 | { 58 | DEBUG_PORT.begin(9600); 59 | DEBUG_PORT.println( F("NMEAdistance.ino started.") ); 60 | DEBUG_PORT.println( F("Looking for GPS device on " GPS_PORT_NAME) ); 61 | 62 | gpsPort.begin(9600); 63 | 64 | } // setup 65 | 66 | void loop() 67 | { 68 | while (gps.available( gpsPort )) { 69 | gps_fix fix = gps.read(); // save the latest 70 | 71 | // When we have a location, calculate how far away we are from the base location. 72 | if (fix.valid.location) { 73 | float range = fix.location.DistanceMiles( base ); 74 | 75 | DEBUG_PORT.print( F("Range: ") ); 76 | DEBUG_PORT.print( range ); 77 | DEBUG_PORT.println( F(" Miles") ); 78 | } else 79 | // Waiting... 80 | DEBUG_PORT.print( '.' ); 81 | } 82 | } // loop 83 | -------------------------------------------------------------------------------- /src/GPSTime.h: -------------------------------------------------------------------------------- 1 | #ifndef GPSTIME_H 2 | #define GPSTIME_H 3 | 4 | // Copyright (C) 2014-2017, SlashDevin 5 | // 6 | // This file is part of NeoGPS 7 | // 8 | // NeoGPS is free software: you can redistribute it and/or modify 9 | // it under the terms of the GNU General Public License as published by 10 | // the Free Software Foundation, either version 3 of the License, or 11 | // (at your option) any later version. 12 | // 13 | // NeoGPS is distributed in the hope that it will be useful, 14 | // but WITHOUT ANY WARRANTY; without even the implied warranty of 15 | // MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the 16 | // GNU General Public License for more details. 17 | // 18 | // You should have received a copy of the GNU General Public License 19 | // along with NeoGPS. If not, see . 20 | 21 | #include "NeoTime.h" 22 | 23 | class GPSTime 24 | { 25 | GPSTime(); 26 | 27 | static NeoGPS::clock_t s_start_of_week; 28 | 29 | public: 30 | 31 | /** 32 | * GPS time is offset from UTC by a number of leap seconds. To convert a GPS 33 | * time to UTC time, the current number of leap seconds must be known. 34 | * See http://en.wikipedia.org/wiki/Global_Positioning_System#Leap_seconds 35 | */ 36 | static uint8_t leap_seconds; 37 | 38 | /** 39 | * Some receivers report time WRT start of the current week, defined as 40 | * Sunday 00:00:00. To save fairly expensive date/time calculations, 41 | * the UTC start of week is cached 42 | */ 43 | static void start_of_week( NeoGPS::time_t & now ) 44 | { 45 | now.set_day(); 46 | s_start_of_week = 47 | (NeoGPS::clock_t) now - 48 | (NeoGPS::clock_t) ((((now.day-1 ) * 24L + 49 | now.hours ) * 60L + 50 | now.minutes) * 60L + 51 | now.seconds); 52 | } 53 | 54 | static NeoGPS::clock_t start_of_week() 55 | { 56 | return s_start_of_week; 57 | } 58 | 59 | /* 60 | * Convert a GPS time-of-week to UTC. 61 | * Requires /leap_seconds/ and /start_of_week/. 62 | */ 63 | static NeoGPS::clock_t TOW_to_UTC( uint32_t time_of_week ) 64 | { return (NeoGPS::clock_t) 65 | (start_of_week() + time_of_week - leap_seconds); } 66 | 67 | /** 68 | * Set /fix/ timestamp from a GPS time-of-week in milliseconds. 69 | * Requires /leap_seconds/ and /start_of_week/. 70 | **/ 71 | static bool from_TOWms 72 | ( uint32_t time_of_week_ms, NeoGPS::time_t &dt, uint16_t &ms ) 73 | { 74 | //trace << PSTR("from_TOWms(") << time_of_week_ms << PSTR("), sow = ") << start_of_week() << PSTR(", leap = ") << leap_seconds << endl; 75 | bool ok = (start_of_week() != 0) && (leap_seconds != 0); 76 | if (ok) { 77 | NeoGPS::clock_t tow_s = time_of_week_ms/1000UL; 78 | dt = TOW_to_UTC( tow_s ); 79 | ms = (uint16_t)(time_of_week_ms - tow_s*1000UL); 80 | } 81 | return ok; 82 | } 83 | }; 84 | 85 | #endif -------------------------------------------------------------------------------- /src/ublox/ubx_cfg.h: -------------------------------------------------------------------------------- 1 | #ifndef UBX_CFG_H 2 | #define UBX_CFG_H 3 | 4 | // Copyright (C) 2014-2017, SlashDevin 5 | // 6 | // This file is part of NeoGPS 7 | // 8 | // NeoGPS is free software: you can redistribute it and/or modify 9 | // it under the terms of the GNU General Public License as published by 10 | // the Free Software Foundation, either version 3 of the License, or 11 | // (at your option) any later version. 12 | // 13 | // NeoGPS is distributed in the hope that it will be useful, 14 | // but WITHOUT ANY WARRANTY; without even the implied warranty of 15 | // MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the 16 | // GNU General Public License for more details. 17 | // 18 | // You should have received a copy of the GNU General Public License 19 | // along with NeoGPS. If not, see . 20 | 21 | //-------------------------------------------------------------------- 22 | // Enable/disable the parsing of specific UBX messages. 23 | // 24 | // Configuring out a message prevents its fields from being parsed. 25 | // However, the message type will still be recognized by /decode/ and 26 | // stored in member /rx_msg/. No valid flags would be available. 27 | 28 | #define UBLOX_PARSE_STATUS 29 | #define UBLOX_PARSE_TIMEGPS 30 | #define UBLOX_PARSE_TIMEUTC 31 | #define UBLOX_PARSE_POSLLH 32 | //#define UBLOX_PARSE_DOP 33 | //#define UBLOX_PARSE_PVT 34 | #define UBLOX_PARSE_VELNED 35 | //#define UBLOX_PARSE_SVINFO 36 | //#define UBLOX_PARSE_CFGNAV5 37 | //#define UBLOX_PARSE_MONVER 38 | //#define UBLOX_PARSE_HNR_PVT 39 | 40 | #if defined(UBLOX_PARSE_DOP) & \ 41 | ( !defined(GPS_FIX_HDOP) & \ 42 | !defined(GPS_FIX_VDOP) & \ 43 | !defined(GPS_FIX_PDOP) ) 44 | #warning UBX DOP message is enabled, but all gps_fix DOP members are disabled. 45 | #endif 46 | 47 | //-------------------------------------------------------------------- 48 | // Identify the last UBX message in an update interval. 49 | // (There are two parts to a UBX message, the class and the ID.) 50 | // For coherency, you must determine which UBX message is last! 51 | // This section *should* pick the correct last UBX message. 52 | 53 | #if defined(UBLOX_PARSE_HNR_PVT) 54 | #define UBX_LAST_MSG_CLASS_IN_INTERVAL ublox::UBX_HNR 55 | #define UBX_LAST_MSG_ID_IN_INTERVAL ublox::UBX_HNR_PVT 56 | #else 57 | #define UBX_LAST_MSG_CLASS_IN_INTERVAL ublox::UBX_NAV 58 | 59 | #if defined(UBLOX_PARSE_VELNED) 60 | #define UBX_LAST_MSG_ID_IN_INTERVAL ublox::UBX_NAV_VELNED 61 | #elif defined(UBLOX_PARSE_DOP) 62 | #define UBX_LAST_MSG_ID_IN_INTERVAL ublox::UBX_NAV_DOP 63 | #elif defined(UBLOX_PARSE_POSLLH) 64 | #define UBX_LAST_MSG_ID_IN_INTERVAL ublox::UBX_NAV_POSLLH 65 | #elif defined(UBLOX_PARSE_STATUS) 66 | #define UBX_LAST_MSG_ID_IN_INTERVAL ublox::UBX_NAV_STATUS 67 | #elif defined(UBLOX_PARSE_PVT) 68 | #define UBX_LAST_MSG_ID_IN_INTERVAL ublox::UBX_NAV_PVT 69 | #elif defined(UBLOX_PARSE_SVINFO) 70 | #define UBX_LAST_MSG_ID_IN_INTERVAL ublox::UBX_NAV_SVINFO 71 | #endif 72 | #endif 73 | 74 | #endif -------------------------------------------------------------------------------- /extras/doc/Location.md: -------------------------------------------------------------------------------- 1 | Location 2 | ======== 3 | The `Location_t` class is a 2D point, containing a latitude and longitude in integer degrees * 107 (source [here](/src/Location.h)). 4 | 5 | This class also provides geographic distance, bearing and offset functions. Furthermore, they all take advantage of the increased precision of the integer coordinates. Other libraries use floating-point coordinates, which have only 6 or 7 significant digits. By using integer math, calculations maintain their original accuracy as long as possible. For example, small distances can be calculated to millimeter accuracy. 6 | 7 | The example program [NMEAaverage.ino](/examples/NMEAaverage/NMEAaverage.ino) shows several techniques for performing 2D calculations. 8 | 9 | ### Distance 10 | 11 | To calculate the distance between a pre-determined point and the current fix, 12 | 13 | ``` 14 | NeoGPS::Location_t madrid( 404381311L, -38196229L ); // see https://www.google.com/maps/@40.4381311,-3.8196229,6z 15 | gps_fix fix; 16 | 17 | void loop() 18 | { 19 | while (gps.available( gps_port )) { 20 | fix = gps.read(); 21 | float dist = fix.location.DistanceKm( madrid ); 22 | // or dist = NeoGPS::Location_t::DistanceKm( fix.location, madrid ); 23 | Serial.print( dist ); 24 | Serial.println( F(" km") ); 25 | ``` 26 | 27 | `DistanceMiles` is also available 28 | 29 | ### Bearing 30 | 31 | To calculate the bearing from one point to another (in radians, CW from North), 32 | 33 | ``` 34 | float bearing = fix.location.BearingToDegrees( madrid ); 35 | // or bearing = NeoGPS::Location_t::BearingToDegrees( fix.location, madrid ); 36 | ``` 37 | Radians is returned by `BearingTo`. 38 | 39 | ### Offsetting a Location 40 | 41 | To move a location by a specified distance, in a specified direction, 42 | 43 | ``` 44 | float bearing = fix.location.BearingToDegrees( madrid ); 45 | // or bearing = NeoGPS::Location_t::BearingToDegrees( fix.location, madrid ); 46 | 47 | // Step 10km closer to the destination 48 | Location_t next_stop( fix.location ); 49 | next_stop.OffsetBy( bearing, 10 / NeoGPS::Location_t::EARTH_RADIUS_KM ); 50 | ``` 51 | Notice that the distance is specified in *radians*. To convert from km to radians, divide by the Earth's radius in km. To convert from miles, divide the miles by the Earth's radius in miles. 52 | 53 | ### NeoGPS namespace 54 | Because the `Location_t` is inside the `NeoGPS` namespace, any time you want to declare your own instance, use any of the constants in that class (anything that requires the `Location_t` name), you must prefix it with `NeoGPS::` (shown above). As with any C++ namespace, you can relax that requirement by putting this statement anywhere after the NeoGPS includes: 55 | 56 | ``` 57 | using namespace NeoGPS; 58 | ``` 59 | 60 | This technique is used in the **NMEAaverage.ino** sketch. 61 | 62 | However, if you have any other libraries that declare their own `Location_t` (not likely), you could not use the `using` statement. `Time_t` is inside the `NeoGPS` namespace for the same reason: avoiding name collisions. 63 | -------------------------------------------------------------------------------- /extras/configs/DTL/NeoGPS_cfg.h: -------------------------------------------------------------------------------- 1 | #ifndef NEOGPS_CFG 2 | #define NEOGPS_CFG 3 | 4 | /** 5 | * Enable/disable packed data structures. 6 | * 7 | * Enabling packed data structures will use two less-portable language 8 | * features of GCC to reduce RAM requirements. Although it was expected to slightly increase execution time and code size, the reverse is true on 8-bit AVRs: the code is smaller and faster with packing enabled. 9 | * 10 | * Disabling packed data structures will be very portable to other 11 | * platforms. NeoGPS configurations will use slightly more RAM, and on 12 | * 8-bit AVRs, the speed is slightly slower, and the code is slightly 13 | * larger. There may be no choice but to disable packing on processors 14 | * that do not support packed structures. 15 | * 16 | * There may also be compiler-specific switches that affect packing and the 17 | * code which accesses packed members. YMMV. 18 | **/ 19 | 20 | #ifdef __AVR__ 21 | #define NEOGPS_PACKED_DATA 22 | #endif 23 | 24 | //------------------------------------------------------------------------ 25 | // Based on the above define, choose which set of packing macros should 26 | // be used in the rest of the NeoGPS package. Do not change these defines. 27 | 28 | #ifdef NEOGPS_PACKED_DATA 29 | 30 | // This is for specifying the number of bits to be used for a 31 | // member of a struct. Booleans are typically one bit. 32 | #define NEOGPS_BF(b) :b 33 | 34 | // This is for requesting the compiler to pack the struct or class members 35 | // "as closely as possible". This is a compiler-dependent interpretation. 36 | #define NEOGPS_PACKED __attribute__((packed)) 37 | 38 | #else 39 | 40 | // Let the compiler do whatever it wants. 41 | 42 | #define NEOGPS_PACKED 43 | #define NEOGPS_BF(b) 44 | 45 | #endif 46 | 47 | /* 48 | * Accommodate C++ compiler and IDE changes. 49 | * 50 | * Declaring constants as class data instead of instance data helps avoid 51 | * collisions with #define names, and allows the compiler to perform more 52 | * checks on their usage. 53 | * 54 | * Until C++ 10 and IDE 1.6.8, initialized class data constants 55 | * were declared like this: 56 | * 57 | * static const = ; 58 | * 59 | * Now, non-simple types (e.g., float) must be declared as 60 | * 61 | * static constexpr = ; 62 | * 63 | * The good news is that this allows the compiler to optimize out an 64 | * expression that is "promised" to be "evaluatable" as a constant. 65 | * The bad news is that it introduces a new language keyword, and the old 66 | * code raises an error. 67 | * 68 | * TODO: Evaluate the requirement for the "static" keyword. 69 | * TODO: Evaluate using a C++ version preprocessor symbol for the #if. 70 | * 71 | * The CONST_CLASS_DATA define will expand to the appropriate keywords. 72 | * 73 | */ 74 | 75 | #if ARDUINO < 10606 76 | 77 | #define CONST_CLASS_DATA static const 78 | 79 | #else 80 | 81 | #define CONST_CLASS_DATA static constexpr 82 | 83 | #endif 84 | 85 | #endif 86 | -------------------------------------------------------------------------------- /extras/configs/Full/NeoGPS_cfg.h: -------------------------------------------------------------------------------- 1 | #ifndef NEOGPS_CFG 2 | #define NEOGPS_CFG 3 | 4 | /** 5 | * Enable/disable packed data structures. 6 | * 7 | * Enabling packed data structures will use two less-portable language 8 | * features of GCC to reduce RAM requirements. Although it was expected to slightly increase execution time and code size, the reverse is true on 8-bit AVRs: the code is smaller and faster with packing enabled. 9 | * 10 | * Disabling packed data structures will be very portable to other 11 | * platforms. NeoGPS configurations will use slightly more RAM, and on 12 | * 8-bit AVRs, the speed is slightly slower, and the code is slightly 13 | * larger. There may be no choice but to disable packing on processors 14 | * that do not support packed structures. 15 | * 16 | * There may also be compiler-specific switches that affect packing and the 17 | * code which accesses packed members. YMMV. 18 | **/ 19 | 20 | #ifdef __AVR__ 21 | #define NEOGPS_PACKED_DATA 22 | #endif 23 | 24 | //------------------------------------------------------------------------ 25 | // Based on the above define, choose which set of packing macros should 26 | // be used in the rest of the NeoGPS package. Do not change these defines. 27 | 28 | #ifdef NEOGPS_PACKED_DATA 29 | 30 | // This is for specifying the number of bits to be used for a 31 | // member of a struct. Booleans are typically one bit. 32 | #define NEOGPS_BF(b) :b 33 | 34 | // This is for requesting the compiler to pack the struct or class members 35 | // "as closely as possible". This is a compiler-dependent interpretation. 36 | #define NEOGPS_PACKED __attribute__((packed)) 37 | 38 | #else 39 | 40 | // Let the compiler do whatever it wants. 41 | 42 | #define NEOGPS_PACKED 43 | #define NEOGPS_BF(b) 44 | 45 | #endif 46 | 47 | /* 48 | * Accommodate C++ compiler and IDE changes. 49 | * 50 | * Declaring constants as class data instead of instance data helps avoid 51 | * collisions with #define names, and allows the compiler to perform more 52 | * checks on their usage. 53 | * 54 | * Until C++ 10 and IDE 1.6.8, initialized class data constants 55 | * were declared like this: 56 | * 57 | * static const = ; 58 | * 59 | * Now, non-simple types (e.g., float) must be declared as 60 | * 61 | * static constexpr = ; 62 | * 63 | * The good news is that this allows the compiler to optimize out an 64 | * expression that is "promised" to be "evaluatable" as a constant. 65 | * The bad news is that it introduces a new language keyword, and the old 66 | * code raises an error. 67 | * 68 | * TODO: Evaluate the requirement for the "static" keyword. 69 | * TODO: Evaluate using a C++ version preprocessor symbol for the #if. 70 | * 71 | * The CONST_CLASS_DATA define will expand to the appropriate keywords. 72 | * 73 | */ 74 | 75 | #if ARDUINO < 10606 76 | 77 | #define CONST_CLASS_DATA static const 78 | 79 | #else 80 | 81 | #define CONST_CLASS_DATA static constexpr 82 | 83 | #endif 84 | 85 | #endif 86 | -------------------------------------------------------------------------------- /extras/configs/Minimal/NeoGPS_cfg.h: -------------------------------------------------------------------------------- 1 | #ifndef NEOGPS_CFG 2 | #define NEOGPS_CFG 3 | 4 | /** 5 | * Enable/disable packed data structures. 6 | * 7 | * Enabling packed data structures will use two less-portable language 8 | * features of GCC to reduce RAM requirements. Although it was expected to slightly increase execution time and code size, the reverse is true on 8-bit AVRs: the code is smaller and faster with packing enabled. 9 | * 10 | * Disabling packed data structures will be very portable to other 11 | * platforms. NeoGPS configurations will use slightly more RAM, and on 12 | * 8-bit AVRs, the speed is slightly slower, and the code is slightly 13 | * larger. There may be no choice but to disable packing on processors 14 | * that do not support packed structures. 15 | * 16 | * There may also be compiler-specific switches that affect packing and the 17 | * code which accesses packed members. YMMV. 18 | **/ 19 | 20 | #ifdef __AVR__ 21 | #define NEOGPS_PACKED_DATA 22 | #endif 23 | 24 | //------------------------------------------------------------------------ 25 | // Based on the above define, choose which set of packing macros should 26 | // be used in the rest of the NeoGPS package. Do not change these defines. 27 | 28 | #ifdef NEOGPS_PACKED_DATA 29 | 30 | // This is for specifying the number of bits to be used for a 31 | // member of a struct. Booleans are typically one bit. 32 | #define NEOGPS_BF(b) :b 33 | 34 | // This is for requesting the compiler to pack the struct or class members 35 | // "as closely as possible". This is a compiler-dependent interpretation. 36 | #define NEOGPS_PACKED __attribute__((packed)) 37 | 38 | #else 39 | 40 | // Let the compiler do whatever it wants. 41 | 42 | #define NEOGPS_PACKED 43 | #define NEOGPS_BF(b) 44 | 45 | #endif 46 | 47 | /* 48 | * Accommodate C++ compiler and IDE changes. 49 | * 50 | * Declaring constants as class data instead of instance data helps avoid 51 | * collisions with #define names, and allows the compiler to perform more 52 | * checks on their usage. 53 | * 54 | * Until C++ 10 and IDE 1.6.8, initialized class data constants 55 | * were declared like this: 56 | * 57 | * static const = ; 58 | * 59 | * Now, non-simple types (e.g., float) must be declared as 60 | * 61 | * static constexpr = ; 62 | * 63 | * The good news is that this allows the compiler to optimize out an 64 | * expression that is "promised" to be "evaluatable" as a constant. 65 | * The bad news is that it introduces a new language keyword, and the old 66 | * code raises an error. 67 | * 68 | * TODO: Evaluate the requirement for the "static" keyword. 69 | * TODO: Evaluate using a C++ version preprocessor symbol for the #if. 70 | * 71 | * The CONST_CLASS_DATA define will expand to the appropriate keywords. 72 | * 73 | */ 74 | 75 | #if ARDUINO < 10606 76 | 77 | #define CONST_CLASS_DATA static const 78 | 79 | #else 80 | 81 | #define CONST_CLASS_DATA static constexpr 82 | 83 | #endif 84 | 85 | #endif 86 | -------------------------------------------------------------------------------- /extras/configs/Nominal/NeoGPS_cfg.h: -------------------------------------------------------------------------------- 1 | #ifndef NEOGPS_CFG 2 | #define NEOGPS_CFG 3 | 4 | /** 5 | * Enable/disable packed data structures. 6 | * 7 | * Enabling packed data structures will use two less-portable language 8 | * features of GCC to reduce RAM requirements. Although it was expected to slightly increase execution time and code size, the reverse is true on 8-bit AVRs: the code is smaller and faster with packing enabled. 9 | * 10 | * Disabling packed data structures will be very portable to other 11 | * platforms. NeoGPS configurations will use slightly more RAM, and on 12 | * 8-bit AVRs, the speed is slightly slower, and the code is slightly 13 | * larger. There may be no choice but to disable packing on processors 14 | * that do not support packed structures. 15 | * 16 | * There may also be compiler-specific switches that affect packing and the 17 | * code which accesses packed members. YMMV. 18 | **/ 19 | 20 | #ifdef __AVR__ 21 | #define NEOGPS_PACKED_DATA 22 | #endif 23 | 24 | //------------------------------------------------------------------------ 25 | // Based on the above define, choose which set of packing macros should 26 | // be used in the rest of the NeoGPS package. Do not change these defines. 27 | 28 | #ifdef NEOGPS_PACKED_DATA 29 | 30 | // This is for specifying the number of bits to be used for a 31 | // member of a struct. Booleans are typically one bit. 32 | #define NEOGPS_BF(b) :b 33 | 34 | // This is for requesting the compiler to pack the struct or class members 35 | // "as closely as possible". This is a compiler-dependent interpretation. 36 | #define NEOGPS_PACKED __attribute__((packed)) 37 | 38 | #else 39 | 40 | // Let the compiler do whatever it wants. 41 | 42 | #define NEOGPS_PACKED 43 | #define NEOGPS_BF(b) 44 | 45 | #endif 46 | 47 | /* 48 | * Accommodate C++ compiler and IDE changes. 49 | * 50 | * Declaring constants as class data instead of instance data helps avoid 51 | * collisions with #define names, and allows the compiler to perform more 52 | * checks on their usage. 53 | * 54 | * Until C++ 10 and IDE 1.6.8, initialized class data constants 55 | * were declared like this: 56 | * 57 | * static const = ; 58 | * 59 | * Now, non-simple types (e.g., float) must be declared as 60 | * 61 | * static constexpr = ; 62 | * 63 | * The good news is that this allows the compiler to optimize out an 64 | * expression that is "promised" to be "evaluatable" as a constant. 65 | * The bad news is that it introduces a new language keyword, and the old 66 | * code raises an error. 67 | * 68 | * TODO: Evaluate the requirement for the "static" keyword. 69 | * TODO: Evaluate using a C++ version preprocessor symbol for the #if. 70 | * 71 | * The CONST_CLASS_DATA define will expand to the appropriate keywords. 72 | * 73 | */ 74 | 75 | #if ARDUINO < 10606 76 | 77 | #define CONST_CLASS_DATA static const 78 | 79 | #else 80 | 81 | #define CONST_CLASS_DATA static constexpr 82 | 83 | #endif 84 | 85 | #endif 86 | -------------------------------------------------------------------------------- /extras/configs/PUBX/NeoGPS_cfg.h: -------------------------------------------------------------------------------- 1 | #ifndef NEOGPS_CFG 2 | #define NEOGPS_CFG 3 | 4 | /** 5 | * Enable/disable packed data structures. 6 | * 7 | * Enabling packed data structures will use two less-portable language 8 | * features of GCC to reduce RAM requirements. Although it was expected to slightly increase execution time and code size, the reverse is true on 8-bit AVRs: the code is smaller and faster with packing enabled. 9 | * 10 | * Disabling packed data structures will be very portable to other 11 | * platforms. NeoGPS configurations will use slightly more RAM, and on 12 | * 8-bit AVRs, the speed is slightly slower, and the code is slightly 13 | * larger. There may be no choice but to disable packing on processors 14 | * that do not support packed structures. 15 | * 16 | * There may also be compiler-specific switches that affect packing and the 17 | * code which accesses packed members. YMMV. 18 | **/ 19 | 20 | #ifdef __AVR__ 21 | #define NEOGPS_PACKED_DATA 22 | #endif 23 | 24 | //------------------------------------------------------------------------ 25 | // Based on the above define, choose which set of packing macros should 26 | // be used in the rest of the NeoGPS package. Do not change these defines. 27 | 28 | #ifdef NEOGPS_PACKED_DATA 29 | 30 | // This is for specifying the number of bits to be used for a 31 | // member of a struct. Booleans are typically one bit. 32 | #define NEOGPS_BF(b) :b 33 | 34 | // This is for requesting the compiler to pack the struct or class members 35 | // "as closely as possible". This is a compiler-dependent interpretation. 36 | #define NEOGPS_PACKED __attribute__((packed)) 37 | 38 | #else 39 | 40 | // Let the compiler do whatever it wants. 41 | 42 | #define NEOGPS_PACKED 43 | #define NEOGPS_BF(b) 44 | 45 | #endif 46 | 47 | /* 48 | * Accommodate C++ compiler and IDE changes. 49 | * 50 | * Declaring constants as class data instead of instance data helps avoid 51 | * collisions with #define names, and allows the compiler to perform more 52 | * checks on their usage. 53 | * 54 | * Until C++ 10 and IDE 1.6.8, initialized class data constants 55 | * were declared like this: 56 | * 57 | * static const = ; 58 | * 59 | * Now, non-simple types (e.g., float) must be declared as 60 | * 61 | * static constexpr = ; 62 | * 63 | * The good news is that this allows the compiler to optimize out an 64 | * expression that is "promised" to be "evaluatable" as a constant. 65 | * The bad news is that it introduces a new language keyword, and the old 66 | * code raises an error. 67 | * 68 | * TODO: Evaluate the requirement for the "static" keyword. 69 | * TODO: Evaluate using a C++ version preprocessor symbol for the #if. 70 | * 71 | * The CONST_CLASS_DATA define will expand to the appropriate keywords. 72 | * 73 | */ 74 | 75 | #if ARDUINO < 10606 76 | 77 | #define CONST_CLASS_DATA static const 78 | 79 | #else 80 | 81 | #define CONST_CLASS_DATA static constexpr 82 | 83 | #endif 84 | 85 | #endif 86 | -------------------------------------------------------------------------------- /extras/configs/Speed/NeoGPS_cfg.h: -------------------------------------------------------------------------------- 1 | #ifndef NEOGPS_CFG 2 | #define NEOGPS_CFG 3 | 4 | /** 5 | * Enable/disable packed data structures. 6 | * 7 | * Enabling packed data structures will use two less-portable language 8 | * features of GCC to reduce RAM requirements. Although it was expected to slightly increase execution time and code size, the reverse is true on 8-bit AVRs: the code is smaller and faster with packing enabled. 9 | * 10 | * Disabling packed data structures will be very portable to other 11 | * platforms. NeoGPS configurations will use slightly more RAM, and on 12 | * 8-bit AVRs, the speed is slightly slower, and the code is slightly 13 | * larger. There may be no choice but to disable packing on processors 14 | * that do not support packed structures. 15 | * 16 | * There may also be compiler-specific switches that affect packing and the 17 | * code which accesses packed members. YMMV. 18 | **/ 19 | 20 | #ifdef __AVR__ 21 | #define NEOGPS_PACKED_DATA 22 | #endif 23 | 24 | //------------------------------------------------------------------------ 25 | // Based on the above define, choose which set of packing macros should 26 | // be used in the rest of the NeoGPS package. Do not change these defines. 27 | 28 | #ifdef NEOGPS_PACKED_DATA 29 | 30 | // This is for specifying the number of bits to be used for a 31 | // member of a struct. Booleans are typically one bit. 32 | #define NEOGPS_BF(b) :b 33 | 34 | // This is for requesting the compiler to pack the struct or class members 35 | // "as closely as possible". This is a compiler-dependent interpretation. 36 | #define NEOGPS_PACKED __attribute__((packed)) 37 | 38 | #else 39 | 40 | // Let the compiler do whatever it wants. 41 | 42 | #define NEOGPS_PACKED 43 | #define NEOGPS_BF(b) 44 | 45 | #endif 46 | 47 | /* 48 | * Accommodate C++ compiler and IDE changes. 49 | * 50 | * Declaring constants as class data instead of instance data helps avoid 51 | * collisions with #define names, and allows the compiler to perform more 52 | * checks on their usage. 53 | * 54 | * Until C++ 10 and IDE 1.6.8, initialized class data constants 55 | * were declared like this: 56 | * 57 | * static const = ; 58 | * 59 | * Now, non-simple types (e.g., float) must be declared as 60 | * 61 | * static constexpr = ; 62 | * 63 | * The good news is that this allows the compiler to optimize out an 64 | * expression that is "promised" to be "evaluatable" as a constant. 65 | * The bad news is that it introduces a new language keyword, and the old 66 | * code raises an error. 67 | * 68 | * TODO: Evaluate the requirement for the "static" keyword. 69 | * TODO: Evaluate using a C++ version preprocessor symbol for the #if. 70 | * 71 | * The CONST_CLASS_DATA define will expand to the appropriate keywords. 72 | * 73 | */ 74 | 75 | #if ARDUINO < 10606 76 | 77 | #define CONST_CLASS_DATA static const 78 | 79 | #else 80 | 81 | #define CONST_CLASS_DATA static constexpr 82 | 83 | #endif 84 | 85 | #endif 86 | -------------------------------------------------------------------------------- /src/Garmin/GrmNMEA.h: -------------------------------------------------------------------------------- 1 | #ifndef _GRMNMEA_H_ 2 | #define _GRMNMEA_H_ 3 | 4 | // Copyright (C) 2014-2017, SlashDevin 5 | // 6 | // This file is part of NeoGPS 7 | // 8 | // NeoGPS is free software: you can redistribute it and/or modify 9 | // it under the terms of the GNU General Public License as published by 10 | // the Free Software Foundation, either version 3 of the License, or 11 | // (at your option) any later version. 12 | // 13 | // NeoGPS is distributed in the hope that it will be useful, 14 | // but WITHOUT ANY WARRANTY; without even the implied warranty of 15 | // MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the 16 | // GNU General Public License for more details. 17 | // 18 | // You should have received a copy of the GNU General Public License 19 | // along with NeoGPS. If not, see . 20 | 21 | #include "NMEAGPS_cfg.h" 22 | 23 | // Disable the entire file if derived types are not allowed. 24 | #ifdef NMEAGPS_DERIVED_TYPES 25 | 26 | #include "NMEAGPS.h" 27 | 28 | #include "Garmin/PGRM_cfg.h" 29 | 30 | #if !defined(GARMINGPS_PARSE_F) 31 | 32 | // No Garmin Proprietary messages defined, ignore rest of file. 33 | 34 | #else 35 | 36 | #if !defined(NMEAGPS_PARSE_PROPRIETARY) 37 | #error NMEAGPS_PARSE_PROPRIETARY must be defined in NMEAGPS_cfg.h in order to parse PGRM messages! 38 | #endif 39 | 40 | #if !defined(NMEAGPS_PARSE_MFR_ID) 41 | #error NMEAGPS_PARSE_MFR_ID must be defined in NMEAGPS_cfg.h in order to parse PGRM messages! 42 | #endif 43 | 44 | 45 | //============================================================= 46 | // NMEA 0183 Parser for Garmin GPS Modules. 47 | // 48 | // @section Limitations 49 | // Very limited support for Garmin proprietary NMEA messages. 50 | // Only NMEA messages of types F are parsed (i.e., $PGRMF). 51 | // 52 | 53 | class GarminNMEA : public NMEAGPS 54 | { 55 | GarminNMEA( const GarminNMEA & ); 56 | 57 | public: 58 | 59 | GarminNMEA() {}; 60 | 61 | /** Garmin proprietary NMEA message types. */ 62 | enum grm_msg_t { 63 | PGRM_BEGIN = NMEA_LAST_MSG, 64 | #if defined(GARMINGPS_PARSE_F) | defined(NMEAGPS_RECOGNIZE_ALL) 65 | PGRMF, 66 | #endif 67 | PGRM_END 68 | }; 69 | static const nmea_msg_t PGRM_FIRST_MSG = (nmea_msg_t) (PGRM_BEGIN+1); 70 | static const nmea_msg_t PGRM_LAST_MSG = (nmea_msg_t) (PGRM_END -1); 71 | 72 | protected: 73 | bool parseField( char chr ); 74 | 75 | bool parseMfrID( char chr ) 76 | { bool ok; 77 | switch (chrCount) { 78 | case 1: ok = (chr == 'G'); break; 79 | case 2: ok = (chr == 'R'); break; 80 | case 3: ok = (chr == 'M'); break; 81 | default: ok = false; 82 | } 83 | return ok; 84 | }; 85 | 86 | bool parseF( char chr ); 87 | 88 | bool parseLeapSeconds( char chr ); 89 | 90 | static const msg_table_t garmin_msg_table __PROGMEM; 91 | 92 | NMEAGPS_VIRTUAL const msg_table_t *msg_table() const 93 | { return &garmin_msg_table; }; 94 | 95 | } NEOGPS_PACKED; 96 | 97 | #endif // at least one GRM message enabled 98 | 99 | #endif // NMEAGPS_DERIVED_TYPES enabled 100 | 101 | #endif -------------------------------------------------------------------------------- /extras/doc/ublox.md: -------------------------------------------------------------------------------- 1 | NeoGPS support for u-blox GPS devices 2 | ================= 3 | To use either ublox-specific NMEA messages ($PUBX) or the UBX binary protocol, you must enable the following in `NMEAGPS_cfg.h`: 4 | ``` 5 | #define NMEAGPS_PARSE_MFR_ID 6 | 7 | #define NMEAGPS_DERIVED_TYPES 8 | ``` 9 | 10 | ## ublox-specific NMEA messages 11 | **NeoGPS** implements the following additional NMEA messages: 12 | 13 | # NMEA 0183 Proprietary Messages 14 | * UBX,00 - Lat/Long Position Data 15 | * UBX,04 - Time of Day and Clock Information 16 | 17 | You may want to change the configured PUBX messages in `PUBX_cfg.h`. It is currently configured to work with the example application, `PUBX.ino`. `PUBX_cfg.h` has the following configuration items: 18 | ``` 19 | #define NMEAGPS_PARSE_PUBX_00 20 | #define NMEAGPS_PARSE_PUBX_04 21 | ``` 22 | 23 | ## ublox-specific binary protocol 24 | 25 | **NeoGPS** implements the following messages in the UBX binary protocol: 26 | 27 | # UBX Protocol Messages 28 | 29 | 30 | 31 | 32 | 33 | 34 | 35 | 36 | 37 | 38 | 39 | 40 |
MessageDescriptionNEO series
NAV_STATUSReceiver Navigation Status

6

NAV_TIMEGPSGPS Time Solution

6

NAV_TIMEUTCUTC Time Solution

6

NAV_POSLLHGeodetic Position Solution

6

NAV_DOPDilutions of precision

6

NAV_PVTNavigation Position Velocity Time Solution

7

NAV_VELNEDVelocity Solution in NED (North/East/Down)

6

NAV_SVINFOSpace Vehicle Information

6

HNR_PVTHigh Rate Output of PVT Solution

8

41 | 42 | You may want to change the configured UBX messages in `ubx_cfg.h`. It is currently configured to work with the example application `ublox.ino`. 43 | 44 | The configuration file `ubx_cfg.h` has the following configuration items near the top of the file: 45 | ``` 46 | #define UBLOX_PARSE_STATUS 47 | #define UBLOX_PARSE_TIMEGPS 48 | #define UBLOX_PARSE_TIMEUTC 49 | #define UBLOX_PARSE_POSLLH 50 | //#define UBLOX_PARSE_DOP 51 | #define UBLOX_PARSE_VELNED 52 | //#define UBLOX_PARSE_PVT 53 | #define UBLOX_PARSE_SVINFO 54 | //#define UBLOX_PARSE_HNR_PVT 55 | ``` 56 | 57 | **Note:** Disabling some of the UBX messages may prevent the `ublox.ino` example sketch from working. That sketch goes through a process of first acquiring the current GPS leap seconds and UTC time so that "time-of-week" milliseconds can be converted to a UTC time. 58 | 59 | The POSLLH and VELNED messages use a Time-Of-Week timestamp. Without the TIMEGPS and TIMEUTC messages, that TOW timestamp cannot be converted to a UTC time. 60 | 61 | * If your application does not need the UTC date and/or time, you could disable the TIMEGPS and TIMEUTC messages. 62 | 63 | * If your application does not need latitude, longitude or altitude, you could disable the POSLLH message. 64 | 65 | * If your application does not need speed or heading, you could disable the VELNED message. 66 | 67 | * If your application does not need satellite information, you could disable the SVINFO message. 68 | -------------------------------------------------------------------------------- /examples/NMEAbenchmark/NMEAbenchmark.ino: -------------------------------------------------------------------------------- 1 | #include 2 | 3 | //====================================================================== 4 | // Program: NMEAbenchmark.ino 5 | // 6 | // Prerequisites: 7 | // 8 | // Description: Use GPGGA and GPRMC sentences to test 9 | // the parser's performance. 10 | // 11 | // GSV sentences are tested if enabled. 12 | // 13 | // 'Serial' is for debug output to the Serial Monitor window. 14 | // 15 | // License: 16 | // Copyright (C) 2014-2017, SlashDevin 17 | // 18 | // This file is part of NeoGPS 19 | // 20 | // NeoGPS is free software: you can redistribute it and/or modify 21 | // it under the terms of the GNU General Public License as published by 22 | // the Free Software Foundation, either version 3 of the License, or 23 | // (at your option) any later version. 24 | // 25 | // NeoGPS is distributed in the hope that it will be useful, 26 | // but WITHOUT ANY WARRANTY; without even the implied warranty of 27 | // MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the 28 | // GNU General Public License for more details. 29 | // 30 | // You should have received a copy of the GNU General Public License 31 | // along with NeoGPS. If not, see . 32 | // 33 | //====================================================================== 34 | 35 | #include 36 | 37 | static NMEAGPS gps; 38 | 39 | //-------------------------- 40 | 41 | static uint32_t time_it( const char *data ) 42 | { 43 | const uint16_t ITERATIONS = 1024; 44 | uint32_t start, end; 45 | 46 | Serial.flush(); 47 | start = micros(); 48 | for (uint16_t i=ITERATIONS; i > 0; i--) { 49 | char *ptr = (char *) data; 50 | while (*ptr) 51 | gps.decode( *ptr++ ); 52 | } 53 | end = micros(); 54 | 55 | return (end-start)/ITERATIONS; 56 | } 57 | 58 | //-------------------------- 59 | 60 | void setup() 61 | { 62 | Serial.begin(9600); 63 | Serial.println( F("NMEAbenchmark: started") ); 64 | Serial.print( F("fix object size = ") ); 65 | Serial.println( sizeof(gps.fix()) ); 66 | Serial.print( F(" gps object size = ") ); 67 | Serial.println( sizeof(gps) ); 68 | 69 | trace_header( Serial ); 70 | 71 | Serial.flush(); 72 | 73 | const char *gga = 74 | "$GPGGA,092725.00,4717.11399,N,00833.91590,E," 75 | "1,8,1.01,499.6,M,48.0,M,,0*5B\r\n"; 76 | const char *gga_no_lat = 77 | "$GPGGA,092725.00,,,00833.91590,E," 78 | "1,8,1.01,499.6,M,48.0,M,,0*0D\r\n"; 79 | 80 | Serial << F("GGA time = ") << time_it( gga ) << '\n'; 81 | trace_all( Serial, gps, gps.fix() ); 82 | 83 | Serial << F("GGA no lat time = ") << time_it( gga_no_lat ) << '\n'; 84 | trace_all( Serial, gps, gps.fix() ); 85 | 86 | const char *rmc = 87 | "$GPRMC,083559.00,A,4717.11437,N,00833.91522,E," 88 | "0.004,77.52,091202,,,A*57\r\n"; 89 | 90 | Serial << F("RMC time = ") << time_it( rmc ) << '\n'; 91 | trace_all( Serial, gps, gps.fix() ); 92 | 93 | #ifdef NMEAGPS_PARSE_GSV 94 | const char *gsv = 95 | "$GPGSV,3,1,10,23,38,230,44,29,71,156,47,07,29,116,41,08,09,081,36*7F\r\n" 96 | "$GPGSV,3,2,10,10,07,189,,05,05,220,,09,34,274,42,18,25,309,44*72\r\n" 97 | "$GPGSV,3,3,10,26,82,187,47,28,43,056,46*77\r\n"; 98 | Serial << F("GSV time = ") << time_it( gsv ) << '\n'; 99 | trace_all( Serial, gps, gps.fix() ); 100 | #endif 101 | } 102 | 103 | //-------------------------- 104 | 105 | void loop() {} 106 | -------------------------------------------------------------------------------- /examples/NMEAGSV/NMEAGSV.ino: -------------------------------------------------------------------------------- 1 | #include 2 | 3 | NMEAGPS gps; // This parses the GPS characters 4 | gps_fix fix; // This holds on to the latest values 5 | 6 | //====================================================================== 7 | // Program: NMEAGSV.ino 8 | // 9 | // Description: Display satellites in view, as reported by the GSV sentences. 10 | // 11 | // Prerequisites: 12 | // 1) NMEA.ino works with your device (correct TX/RX pins and baud rate) 13 | // 2) NMEAGPS_PARSE_SATELLITES and NMEAGPS_PARSE_SATELLITE_INFO are 14 | // enabled in NMEAGPS_cfg.h 15 | // 3) The GSV sentence has been enabled in NMEAGPS_cfg.h. 16 | // 4) Your device emits the GSV sentence (use NMEAorder.ino to confirm). 17 | // 5) LAST_SENTENCE_IN_INTERVAL has been set to GSV (or any other enabled sentence) 18 | // in NMEAGPS_cfg.h (use NMEAorder.ino). 19 | // 20 | // 'Serial' is for debug output to the Serial Monitor window. 21 | // 22 | // License: 23 | // Copyright (C) 2017, SlashDevin 24 | // 25 | // This file is part of NeoGPS 26 | // 27 | // NeoGPS is free software: you can redistribute it and/or modify 28 | // it under the terms of the GNU General Public License as published by 29 | // the Free Software Foundation, either version 3 of the License, or 30 | // (at your option) any later version. 31 | // 32 | // NeoGPS is distributed in the hope that it will be useful, 33 | // but WITHOUT ANY WARRANTY; without even the implied warranty of 34 | // MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the 35 | // GNU General Public License for more details. 36 | // 37 | // You should have received a copy of the GNU General Public License 38 | // along with NeoGPS. If not, see . 39 | // 40 | //====================================================================== 41 | 42 | #include 43 | 44 | //----------------- 45 | // Check configuration 46 | 47 | #ifndef NMEAGPS_PARSE_GSV 48 | #error You must define NMEAGPS_PARSE_GSV in NMEAGPS_cfg.h! 49 | #endif 50 | 51 | #ifndef NMEAGPS_PARSE_SATELLITES 52 | #error You must define NMEAGPS_PARSE_SATELLITE in NMEAGPS_cfg.h! 53 | #endif 54 | 55 | #ifndef NMEAGPS_PARSE_SATELLITE_INFO 56 | #error You must define NMEAGPS_PARSE_SATELLITE_INFO in NMEAGPS_cfg.h! 57 | #endif 58 | 59 | //----------------- 60 | 61 | void setup() 62 | { 63 | DEBUG_PORT.begin(9600); 64 | while (!Serial) 65 | ; 66 | DEBUG_PORT.print( F("NeoGPS GSV example started\n") ); 67 | 68 | gpsPort.begin(9600); 69 | 70 | } // setup 71 | 72 | //----------------- 73 | 74 | void loop() 75 | { 76 | while (gps.available( gpsPort )) { 77 | fix = gps.read(); 78 | 79 | displaySatellitesInView(); 80 | } 81 | 82 | } // loop 83 | 84 | //----------------- 85 | 86 | void displaySatellitesInView() 87 | { 88 | DEBUG_PORT.print( gps.sat_count ); 89 | DEBUG_PORT.print( ',' ); 90 | 91 | for (uint8_t i=0; i < gps.sat_count; i++) { 92 | DEBUG_PORT.print( gps.satellites[i].id ); 93 | DEBUG_PORT.print( ' ' ); 94 | DEBUG_PORT.print( gps.satellites[i].elevation ); 95 | DEBUG_PORT.print( '/' ); 96 | DEBUG_PORT.print( gps.satellites[i].azimuth ); 97 | DEBUG_PORT.print( '@' ); 98 | if (gps.satellites[i].tracked) 99 | DEBUG_PORT.print( gps.satellites[i].snr ); 100 | else 101 | DEBUG_PORT.print( '-' ); 102 | DEBUG_PORT.print( F(", ") ); 103 | } 104 | 105 | DEBUG_PORT.println(); 106 | 107 | } // displaySatellitesInView 108 | -------------------------------------------------------------------------------- /src/Garmin/GrmNMEA.cpp: -------------------------------------------------------------------------------- 1 | // Copyright (C) 2014-2017, SlashDevin 2 | // 3 | // This file is part of NeoGPS 4 | // 5 | // NeoGPS is free software: you can redistribute it and/or modify 6 | // it under the terms of the GNU General Public License as published by 7 | // the Free Software Foundation, either version 3 of the License, or 8 | // (at your option) any later version. 9 | // 10 | // NeoGPS is distributed in the hope that it will be useful, 11 | // but WITHOUT ANY WARRANTY; without even the implied warranty of 12 | // MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the 13 | // GNU General Public License for more details. 14 | // 15 | // You should have received a copy of the GNU General Public License 16 | // along with NeoGPS. If not, see . 17 | 18 | #include "Garmin/GrmNMEA.h" 19 | 20 | // Disable the entire file if derived types are not allowed, 21 | // *or* if no PUBX messages are enabled. 22 | #if defined( NMEAGPS_DERIVED_TYPES) & \ 23 | defined( GARMINGPS_PARSE_F ) 24 | 25 | #include "GPSTime.h" 26 | 27 | //---------------------------------------------------------------- 28 | 29 | bool GarminNMEA::parseField( char chr ) 30 | { 31 | if (nmeaMessage >= (nmea_msg_t) PGRM_FIRST_MSG) { 32 | 33 | switch (nmeaMessage) { 34 | 35 | case PGRMF: return parseF( chr ); 36 | 37 | default: 38 | break; 39 | } 40 | 41 | } else 42 | 43 | // Delegate 44 | return NMEAGPS::parseField(chr); 45 | 46 | 47 | return true; 48 | 49 | } // parseField 50 | 51 | //---------------------------------------------------------------- 52 | // Garmin Proprietary NMEA Sentence strings (alphabetical) 53 | 54 | #if defined(GARMINGPS_PARSE_F) | defined(NMEAGPS_RECOGNIZE_ALL) 55 | static const char garminF[] __PROGMEM = "F"; 56 | #endif 57 | 58 | static const char * const garmin_nmea[] __PROGMEM = 59 | { 60 | #if defined(GARMINGPS_PARSE_F) | defined(NMEAGPS_RECOGNIZE_ALL) 61 | garminF, 62 | #endif 63 | }; 64 | 65 | const NMEAGPS::msg_table_t GarminNMEA::garmin_msg_table __PROGMEM = 66 | { 67 | GarminNMEA::PGRM_FIRST_MSG, 68 | (const msg_table_t *) &NMEAGPS::nmea_msg_table, // <-- link to standard message table 69 | sizeof(garmin_nmea)/sizeof(garmin_nmea[0]), 70 | garmin_nmea 71 | }; 72 | 73 | //---------------------------------------------------------------- 74 | 75 | bool GarminNMEA::parseF( char chr ) 76 | { 77 | #ifdef GARMINGPS_PARSE_F 78 | switch (fieldIndex) { 79 | case 3: return parseDDMMYY( chr ); 80 | case 4: return parseTime( chr ); 81 | case 5: return parseLeapSeconds( chr ); // <-- you will write this 82 | PARSE_LOC(6); 83 | //case 10: return parseFix( char ); // not needed, because next field sets status 84 | case 11: return parseFix( chr ); 85 | case 12: return parseSpeedKph( chr ); 86 | case 13: return parseHeading( chr ); 87 | case 14: return parsePDOP( chr ); 88 | //case 15: return parseTDOP( chr ); // not yet supported 89 | } 90 | #endif 91 | 92 | return true; 93 | 94 | } // parseF 95 | 96 | //---------------------------------------------------------------- 97 | 98 | bool GarminNMEA::parseLeapSeconds( char chr ) 99 | { 100 | static uint8_t newLeapSeconds; // just used for parsing 101 | 102 | if (NMEAGPS::parseInt( newLeapSeconds, chr )) { 103 | GPSTime::leap_seconds = newLeapSeconds; // assign parsed value to global 104 | } 105 | 106 | return true; 107 | 108 | } // parseGPSleapSeconds 109 | 110 | #endif // DERIVED types and at least one PGRM message enabled 111 | -------------------------------------------------------------------------------- /examples/NMEAlocDMS/NMEAlocDMS.ino: -------------------------------------------------------------------------------- 1 | #include 2 | #include 3 | 4 | //====================================================================== 5 | // Program: NMEAlocDMS.ino 6 | // 7 | // Description: This program only parses an RMC sentence for the lat/lon. 8 | // 9 | // Prerequisites: 10 | // 1) NMEA.ino works with your device (correct TX/RX pins and baud rate) 11 | // 2) The RMC sentence has been enabled. 12 | // 3) Your device sends an RMC sentence (e.g., $GPRMC). 13 | // 14 | // Serial is for trace output to the Serial Monitor window. 15 | // 16 | // License: 17 | // Copyright (C) 2014-2017, SlashDevin 18 | // 19 | // This file is part of NeoGPS 20 | // 21 | // NeoGPS is free software: you can redistribute it and/or modify 22 | // it under the terms of the GNU General Public License as published by 23 | // the Free Software Foundation, either version 3 of the License, or 24 | // (at your option) any later version. 25 | // 26 | // NeoGPS is distributed in the hope that it will be useful, 27 | // but WITHOUT ANY WARRANTY; without even the implied warranty of 28 | // MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the 29 | // GNU General Public License for more details. 30 | // 31 | // You should have received a copy of the GNU General Public License 32 | // along with NeoGPS. If not, see . 33 | // 34 | //====================================================================== 35 | 36 | #include 37 | 38 | //------------------------------------------------------------ 39 | // Check that the config files are set up properly 40 | 41 | #if !defined( NMEAGPS_PARSE_RMC ) 42 | #error You must uncomment NMEAGPS_PARSE_RMC in NMEAGPS_cfg.h! 43 | #endif 44 | 45 | #if !defined( GPS_FIX_LOCATION_DMS ) 46 | #error You must uncomment GPS_FIX_LOCATION_DMS in GPSfix_cfg.h! 47 | #endif 48 | 49 | #ifdef NMEAGPS_INTERRUPT_PROCESSING 50 | #error You must *NOT* define NMEAGPS_INTERRUPT_PROCESSING in NMEAGPS_cfg.h! 51 | #endif 52 | 53 | //------------------------------------------------------------ 54 | 55 | static NMEAGPS gps; // This parses the GPS characters 56 | 57 | static void doSomeWork( const gps_fix & fix ); 58 | static void doSomeWork( const gps_fix & fix ) 59 | { 60 | // This is the best place to do your time-consuming work, right after 61 | // the RMC sentence was received. If you do anything in "loop()", 62 | // you could cause GPS characters to be lost, and you will not 63 | // get a good lat/lon. 64 | // For this example, we just print the lat/lon. If you print too much, 65 | // this routine will not get back to "loop()" in time to process 66 | // the next set of GPS data. 67 | 68 | if (fix.valid.location) { 69 | 70 | DEBUG_PORT << fix.latitudeDMS; 71 | DEBUG_PORT.print( fix.latitudeDMS.NS() ); 72 | DEBUG_PORT.write( ' ' ); 73 | if (fix.longitudeDMS.degrees < 100) 74 | DEBUG_PORT.write( '0' ); 75 | DEBUG_PORT << fix.longitudeDMS; 76 | DEBUG_PORT.print( fix.longitudeDMS.EW() ); 77 | 78 | } else { 79 | // No valid location data yet! 80 | DEBUG_PORT.print( '?' ); 81 | } 82 | 83 | DEBUG_PORT.println(); 84 | 85 | } // doSomeWork 86 | 87 | //------------------------------------ 88 | 89 | static void GPSloop(); 90 | static void GPSloop() 91 | { 92 | while (gps.available( gpsPort )) 93 | doSomeWork( gps.read() ); 94 | 95 | } // GPSloop 96 | 97 | //-------------------------- 98 | 99 | void setup() 100 | { 101 | DEBUG_PORT.begin(9600); 102 | while (!DEBUG_PORT) 103 | ; 104 | 105 | DEBUG_PORT.print( F("NMEAlocDMS.INO: started\n") ); 106 | DEBUG_PORT.println( F("Looking for GPS device on " GPS_PORT_NAME) ); 107 | DEBUG_PORT.flush(); 108 | 109 | gpsPort.begin(9600); 110 | } 111 | 112 | //-------------------------- 113 | 114 | void loop() 115 | { 116 | GPSloop(); 117 | } 118 | -------------------------------------------------------------------------------- /src/DMS.cpp: -------------------------------------------------------------------------------- 1 | // Copyright (C) 2014-2017, SlashDevin 2 | // 3 | // This file is part of NeoGPS 4 | // 5 | // NeoGPS is free software: you can redistribute it and/or modify 6 | // it under the terms of the GNU General Public License as published by 7 | // the Free Software Foundation, either version 3 of the License, or 8 | // (at your option) any later version. 9 | // 10 | // NeoGPS is distributed in the hope that it will be useful, 11 | // but WITHOUT ANY WARRANTY; without even the implied warranty of 12 | // MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the 13 | // GNU General Public License for more details. 14 | // 15 | // You should have received a copy of the GNU General Public License 16 | // along with NeoGPS. If not, see . 17 | 18 | #include "DMS.h" 19 | 20 | #include 21 | 22 | //---------------------------------------------------------------- 23 | // Note that no division is used, and shifts are on byte boundaries. Fast! 24 | 25 | void DMS_t::From( int32_t deg_1E7 ) 26 | { 27 | const uint32_t E7 = 10000000UL; 28 | 29 | if (deg_1E7 < 0) { 30 | deg_1E7 = -deg_1E7; 31 | hemisphere = SOUTH_H; // or WEST_H 32 | } else 33 | hemisphere = NORTH_H; // or EAST_H 34 | 35 | const uint32_t div_E32 = 429; // 1e-07 * 2^32 36 | degrees = ((deg_1E7 >> 16) * div_E32) >> 16; 37 | uint32_t remainder = deg_1E7 - degrees * E7; 38 | 39 | remainder *= 60; // to minutes * E7 40 | minutes = ((remainder >> 16) * div_E32) >> 16; 41 | remainder -= minutes * E7; 42 | 43 | remainder *= 60; // to seconds * E7 44 | uint32_t secs = ((remainder >> 16) * div_E32) >> 16; 45 | remainder -= secs * E7; 46 | 47 | const uint32_t div_1E4_E24 = 1677; // 0.00001 * 2^24 48 | seconds_frac = (((remainder >> 8) * div_1E4_E24) >> 16); // thousandths 49 | seconds_whole = secs; 50 | 51 | // Carry if thousandths too big 52 | if (seconds_frac >= 1000) { 53 | seconds_frac -= 1000; 54 | seconds_whole++; 55 | if (seconds_whole >= 60) { 56 | seconds_whole -= 60; 57 | minutes++; 58 | if (minutes >= 60) { 59 | minutes -= 60; 60 | degrees++; 61 | } 62 | } 63 | } 64 | 65 | } // From 66 | 67 | //---------------------------------------------------------------- 68 | 69 | Print & operator << ( Print & outs, const DMS_t & dms ) 70 | { 71 | if (dms.degrees < 10) 72 | outs.write( '0' ); 73 | outs.print( dms.degrees ); 74 | outs.write( ' ' ); 75 | if (dms.minutes < 10) 76 | outs.write( '0' ); 77 | outs.print( dms.minutes ); 78 | outs.print( F("\' ") ); 79 | if (dms.seconds_whole < 10) 80 | outs.write( '0' ); 81 | outs.print( dms.seconds_whole ); 82 | outs.write( '.' ); 83 | if (dms.seconds_frac < 100) 84 | outs.write( '0' ); 85 | if (dms.seconds_frac < 10) 86 | outs.write( '0' ); 87 | outs.print( dms.seconds_frac ); 88 | outs.print( F("\" ") ); 89 | 90 | return outs; 91 | 92 | } // operator << 93 | 94 | //---------------------------------------------------------------- 95 | 96 | void DMS_t::printDDDMMmmmm( Print & outs ) const 97 | { 98 | outs.print( degrees ); 99 | 100 | if (minutes < 10) 101 | outs.print( '0' ); 102 | outs.print( minutes ); 103 | outs.print( '.' ); 104 | 105 | // Calculate the fractional minutes from the seconds, 106 | // *without* using floating-point numbers. 107 | 108 | uint16_t mmmm = seconds_whole * 166; // same as 10000/60, less .66666... 109 | mmmm += (seconds_whole * 2 + seconds_frac/2 ) / 3; // ... plus the remaining .66666 110 | // ... plus the seconds_frac, scaled by 10000/(60*1000) = 1/6, which 111 | // is implemented above as 1/2 * 1/3 112 | 113 | // print leading zeroes, if necessary 114 | if (mmmm < 1000) 115 | outs.print( '0' ); 116 | if (mmmm < 100) 117 | outs.print( '0' ); 118 | if (mmmm < 10) 119 | outs.print( '0' ); 120 | outs.print( mmmm ); 121 | } -------------------------------------------------------------------------------- /src/ublox/ubxNMEA.h: -------------------------------------------------------------------------------- 1 | #ifndef _UBXNMEA_H_ 2 | #define _UBXNMEA_H_ 3 | 4 | // Copyright (C) 2014-2017, SlashDevin 5 | // 6 | // This file is part of NeoGPS 7 | // 8 | // NeoGPS is free software: you can redistribute it and/or modify 9 | // it under the terms of the GNU General Public License as published by 10 | // the Free Software Foundation, either version 3 of the License, or 11 | // (at your option) any later version. 12 | // 13 | // NeoGPS is distributed in the hope that it will be useful, 14 | // but WITHOUT ANY WARRANTY; without even the implied warranty of 15 | // MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the 16 | // GNU General Public License for more details. 17 | // 18 | // You should have received a copy of the GNU General Public License 19 | // along with NeoGPS. If not, see . 20 | 21 | #include "NMEAGPS_cfg.h" 22 | 23 | // Disable the entire file if derived types are not allowed. 24 | #ifdef NMEAGPS_DERIVED_TYPES 25 | 26 | #include "NMEAGPS.h" 27 | 28 | #include "PUBX_cfg.h" 29 | 30 | // Ublox proprietary messages do not have a message type. These 31 | // messages start with "$PUBX," which ends with the manufacturer ID. The 32 | // message type is actually specified by the first numeric field. In order 33 | // to parse these messages, /parse_mfr_ID/ must be overridden to set the 34 | // /nmeaMessage/ to PUBX_00 during /parseCommand/. When the first numeric 35 | // field is completed by /parseField/, it may change /nmeamessage/ to one 36 | // of the other PUBX message types. 37 | 38 | #if !defined(NMEAGPS_PARSE_PUBX_00) & !defined(NMEAGPS_PARSE_PUBX_04) 39 | 40 | // No ublox Proprietary messages defined, ignore rest of file. 41 | #define UBLOXGPS_BASE NMEAGPS 42 | #define UBLOXGPS_BASE_LAST_MSG NMEA_LAST_MSG 43 | #else 44 | 45 | #define UBLOXGPS_BASE ubloxNMEA 46 | #define UBLOXGPS_BASE_LAST_MSG PUBX_LAST_MSG 47 | 48 | #if !defined(NMEAGPS_PARSE_PROPRIETARY) 49 | #error NMEAGPS_PARSE_PROPRIETARY must be defined in NMEAGPS_cfg.h in order to parse PUBX messages! 50 | #endif 51 | 52 | #if !defined(NMEAGPS_PARSE_MFR_ID) 53 | #error NMEAGPS_PARSE_MFR_ID must be defined in NMEAGPS_cfg.h in order to parse PUBX messages! 54 | #endif 55 | 56 | //============================================================= 57 | // NMEA 0183 Parser for ublox Neo-6 GPS Modules. 58 | // 59 | // @section Limitations 60 | // Very limited support for ublox proprietary NMEA messages. 61 | // Only NMEA messages of types PUBX,00 and PUBX,04 are parsed. 62 | // 63 | 64 | class ubloxNMEA : public NMEAGPS 65 | { 66 | ubloxNMEA( const ubloxNMEA & ); 67 | 68 | public: 69 | 70 | ubloxNMEA() {}; 71 | 72 | /** ublox proprietary NMEA message types. */ 73 | enum pubx_msg_t { 74 | PUBX_00 = NMEA_LAST_MSG+1, 75 | #if defined(NMEAGPS_PARSE_PUBX_04) | defined(NMEAGPS_RECOGNIZE_ALL) 76 | PUBX_04, 77 | #endif 78 | PUBX_END 79 | }; 80 | static const nmea_msg_t PUBX_FIRST_MSG = (nmea_msg_t) PUBX_00; 81 | static const nmea_msg_t PUBX_LAST_MSG = (nmea_msg_t) (PUBX_END-1); 82 | 83 | protected: 84 | bool parseMfrID( char chr ) 85 | { bool ok; 86 | switch (chrCount) { 87 | case 1: ok = (chr == 'U'); break; 88 | case 2: ok = (chr == 'B'); break; 89 | default: if (chr == 'X') { 90 | ok = true; 91 | nmeaMessage = (nmea_msg_t) PUBX_00; 92 | } else 93 | ok = false; 94 | break; 95 | } 96 | return ok; 97 | }; 98 | 99 | bool parsePUBX_00( char chr ); 100 | bool parsePUBX_04( char chr ); 101 | 102 | bool parseField( char chr ); 103 | 104 | bool parseFix( char chr ); 105 | bool parseVelocityDown( char chr ); 106 | 107 | } NEOGPS_PACKED; 108 | 109 | #endif // at least one PUBX message enabled 110 | 111 | #endif // NMEAGPS_DERIVED_TYPES enabled 112 | 113 | #endif 114 | -------------------------------------------------------------------------------- /README.md: -------------------------------------------------------------------------------- 1 | NeoGPS 2 | ====== 3 | 4 | This fully-configurable Arduino library uses _**minimal**_ RAM, PROGMEM and CPU time, 5 | requiring as few as _**10 bytes of RAM**_, **866 bytes of PROGMEM**, and **less than 1mS of CPU time** per sentence. 6 | 7 | It supports the following protocols and messages: 8 | 9 | #### NMEA 0183 10 | * GPGGA - System fix data 11 | * GPGLL - Geographic Latitude and Longitude 12 | * GPGSA - DOP and active satellites 13 | * GPGST - Pseudo Range Error Statistics 14 | * GPGSV - Satellites in View 15 | * GPRMC - Recommended Minimum specific GPS/Transit data 16 | * GPVTG - Course over ground and Ground speed 17 | * GPZDA - UTC Time and Date 18 | 19 | The "GP" prefix usually indicates an original [GPS](https://en.wikipedia.org/wiki/Satellite_navigation#GPS) source. NeoGPS parses *all* Talker IDs, including 20 | * "GL" ([GLONASS](https://en.wikipedia.org/wiki/Satellite_navigation#GLONASS)), 21 | * "BD" or "GB" ([BeiDou](https://en.wikipedia.org/wiki/Satellite_navigation#BeiDou)), 22 | * "GA" ([Galileo](https://en.wikipedia.org/wiki/Satellite_navigation#Galileo)), and 23 | * "GN" (mixed) 24 | 25 | This means that GLRMC, GBRMC or BDRMC, GARMC and GNRMC from the latest GPS devices (e.g., ublox M8N) will also be correctly parsed. See discussion of Talker IDs in [Configurations](extras/doc/Configurations.md#enabledisable-the-talker-id-and-manufacturer-id-processing). 26 | 27 | Most applications can be fully implemented with the standard NMEA messages above. They are supported by almost all GPS manufacturers. Additional messages can be added through derived classes (see ublox and Garmin sections below). 28 | 29 | Most applications will use this simple, familiar loop structure: 30 | ``` 31 | NMEAGPS gps; 32 | gps_fix fix; 33 | 34 | void loop() 35 | { 36 | while (gps.available( gps_port )) { 37 | fix = gps.read(); 38 | doSomeWork( fix ); 39 | } 40 | } 41 | ``` 42 | For more information on this loop, see the [Usage](extras/doc/Data%20Model.md#usage) section on the [Data Model](extras/doc/Data%20Model.md) page. 43 | 44 | (This is the plain Arduino version of the [CosaGPS](https://github.com/SlashDevin/CosaGPS) library for [Cosa](https://github.com/mikaelpatel/Cosa).) 45 | 46 | Goals 47 | ====== 48 | In an attempt to be reusable in a variety of different programming styles, this library supports: 49 | * resource-constrained environments (e.g., ATTINY targets) 50 | * sync or async operation (reading in `loop()` vs interrupt processing) 51 | * event or polling (deferred handling vs. continuous calls in `loop()`) 52 | * coherent fixes (merged from multiple sentences) vs. individual sentences 53 | * optional buffering of fixes 54 | * optional floating point 55 | * configurable message sets, including hooks for implementing proprietary NMEA messages 56 | * configurable message fields 57 | * multiple protocols from same device 58 | * any kind of input stream (Serial, [NeoSWSerial](https://github.com/SlashDevin/NeoSWSerial), I2C, PROGMEM arrays, etc.) 59 | 60 | Inconceivable! 61 | ============= 62 | 63 | Don't believe it? Check out these detailed sections: 64 | 65 | Section | Description 66 | -------- | ------------ 67 | [License](LICENSE) | The Fine Print 68 | [Installing](extras/doc/Installing.md) | Copying files 69 | [Data Model](extras/doc/Data%20Model.md) | How to parse and use GPS data 70 | [Configurations](extras/doc/Configurations.md) | Tailoring NeoGPS to your needs 71 | [Performance](extras/doc/Performance.md) | 37% to 72% faster! Really! 72 | [RAM requirements](extras/doc/RAM.md) | Doing it without buffers! 73 | [Program Space requirements](extras/doc/Program.md) | Making it fit 74 | [Examples](extras/doc/Examples.md) | Programming styles 75 | [Troubleshooting](extras/doc/Troubleshooting.md) | Troubleshooting 76 | [Extending NeoGPS](extras/doc/Extending.md) | Using specific devices 77 | [ublox](extras/doc/ublox.md) | ublox-specific code 78 | [Garmin](extras/doc/Garmin.md) | Garmin-specific code 79 | [Tradeoffs](extras/doc/Tradeoffs.md) | Comparing to other libraries 80 | [Acknowledgements](extras/doc/Acknowledgements.md) | Thanks! 81 | -------------------------------------------------------------------------------- /extras/doc/Merging.md: -------------------------------------------------------------------------------- 1 | Merging 2 | =========== 3 | Because different NMEA sentences contain different pieces of a fix, they have to be "merged" to determine a complete picture. Some sentences contain only date and time. Others contain location and altitude, but not speed and heading (see table [here](Choosing.md)). 4 | 5 | There are several ways to use the GPS fix data: without merging, implicit merging, and **explicit merging ([the default](#3-explicit-merging))**. NeoGPS allows you to choose how you want multiple sentences to be merged: 6 | 7 | ### 1. NO MERGING 8 | 9 | In this mode, `gps.read()` will return a fix that is populated from just one sentence. You will probably receive multiple sentences per update interval, depending on your GPS device. 10 | 11 | If you are interested in just a few pieces of information, and those pieces can be obtained from one or two sentences, you can wait for that specific sentence to arrive, and then use one or more members of the fix at that time. Make sure that "no merging" is selected in NMEAGPS_cfg.h by commenting out these lines: 12 | ``` 13 | //#define NMEAGPS_EXPLICIT_MERGING 14 | //#define NMEAGPS_IMPLICIT_MERGING 15 | ``` 16 | Then write your loop to wait for the specific sentence: 17 | ``` 18 | void loop() 19 | { 20 | while (gps.available( gps_port )) { 21 | const gps_fix & rmc = gps.read(); 22 | 23 | if (gps.nmeaMessage == NMEAGPS::NMEA_RMC) { 24 | // All GPS-related work is performed inside this if statement 25 | 26 | if (rmc.valid.speed && (rmc.speed <= 5)) 27 | Serial.println( F("Too slow!") ); 28 | 29 | if (rmc.valid.location && ... or any rmc member 30 | } 31 | } 32 | 33 | // Can't access rmc out here... 34 | ``` 35 | If you are interested in pieces of information that are grouped by some detailed criteria (e.g., field values), you must select "no merging" and then manually merge the fixes of interest. The `merged` copy will be safe to access at any time: 36 | ``` 37 | gps_fix merged; 38 | 39 | void loop() 40 | { 41 | while (gps.available( gps_port )) { 42 | const gps_fix & fix = gps.read(); 43 | 44 | if ((gps.nmeaMessage == NMEAGPS::NMEA_RMC) && 45 | (fix.valid.heading && 46 | ((4500 <= fix.heading_cd()) && (fix.heading_cd() < 9000)))){ 47 | 48 | merged |= fix; 49 | 50 | if (merged.valid.satellites && (rmc.satellites > 5)) 51 | Serial.println( F("Moar sats!") ); 52 | } 53 | } 54 | 55 | // Can't access 'fix' out here, but 'merged' can be used... 56 | ``` 57 | ### 2. IMPLICIT MERGING 58 | If you are interested in more pieces of information, perhaps requiring more kinds of sentences to be decoded, but don't really care about what time the pieces were received, you could enable implicit merging: 59 | ``` 60 | //#define NMEAGPS_EXPLICIT_MERGING 61 | #define NMEAGPS_IMPLICIT_MERGING 62 | ``` 63 | As sentences are received, they are accumulated internally. Previous field values are retained until they are overwritten by another sentence. When `gps.available`, the accumulated fix can be obtained with `gps.read()`. 64 | 65 | Note: The members in an implicitly-merged fix may not be coherent (see [Coherency](Coherency.md). Also, checksum errors can cause the internal fix to be completely reset. Be sure your sketch checks the [valid flags](Data%20Model.md#validity) before using any fix data. 66 | 67 | ### 3. EXPLICIT MERGING 68 | This is the default setting. To enable explicit merging, make sure this is in NMEAGPS_cfg.h: 69 | ``` 70 | #define NMEAGPS_EXPLICIT_MERGING 71 | //#define NMEAGPS_IMPLICIT_MERGING 72 | 73 | #define NMEAGPS_FIX_MAX 1 74 | ``` 75 | NMEAGPS_FIX_MAX must be at least one to use EXPLICIT merging. 76 | 77 | As sentences are received, they are merged internally. When the LAST_SENTENCE_IN_INTERVAL is received, the internal fix is marked as "available", and it can be accessed by calling `gps.read()`. When the next sentence arrives, the internal fix structure will be emptied. 78 | 79 | ``` 80 | gps_fix_t currentFix; 81 | 82 | void loop() 83 | { 84 | while (gps.available( gps_port )) 85 | currentFix = gps.read(); 86 | 87 | check_position( currentFix ); 88 | ``` 89 | 90 | Explicit merging is also required to implement [Coherency](Coherency.md). 91 | -------------------------------------------------------------------------------- /examples/PGRM/PGRM.ino: -------------------------------------------------------------------------------- 1 | #include 2 | #include 3 | #include 4 | 5 | //====================================================================== 6 | // Program: PGRM.ino 7 | // 8 | // Description: This program parses NMEA proprietary messages from 9 | // Garmin devices. It is an extension of NMEA.ino. 10 | // 11 | // Prerequisites: 12 | // 1) You have a Garmin GPS device 13 | // 2) NMEA.ino works with your device 14 | // 3) At least one NMEA standard or proprietary sentence has been enabled. 15 | // 4) Implicit Merging is disabled. 16 | // 17 | // Serial is for debug output to the Serial Monitor window. 18 | // 19 | // License: 20 | // Copyright (C) 2014-2017, SlashDevin 21 | // 22 | // This file is part of NeoGPS 23 | // 24 | // NeoGPS is free software: you can redistribute it and/or modify 25 | // it under the terms of the GNU General Public License as published by 26 | // the Free Software Foundation, either version 3 of the License, or 27 | // (at your option) any later version. 28 | // 29 | // NeoGPS is distributed in the hope that it will be useful, 30 | // but WITHOUT ANY WARRANTY; without even the implied warranty of 31 | // MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the 32 | // GNU General Public License for more details. 33 | // 34 | // You should have received a copy of the GNU General Public License 35 | // along with NeoGPS. If not, see . 36 | // 37 | //====================================================================== 38 | 39 | #include 40 | #include 41 | 42 | //------------------------------------------------------------ 43 | // Check that the config files are set up properly 44 | 45 | #if !defined( NMEAGPS_PARSE_GGA ) & !defined( NMEAGPS_PARSE_GLL ) & \ 46 | !defined( NMEAGPS_PARSE_GSA ) & !defined( NMEAGPS_PARSE_GSV ) & \ 47 | !defined( NMEAGPS_PARSE_RMC ) & !defined( NMEAGPS_PARSE_VTG ) & \ 48 | !defined( NMEAGPS_PARSE_ZDA ) & !defined( NMEAGPS_PARSE_GST ) & \ 49 | !defined( GARMINGPS_PARSE_F ) 50 | 51 | #error No NMEA sentences enabled: no fix data available. 52 | 53 | #endif 54 | 55 | #if !defined( GARMINGPS_PARSE_F ) 56 | #error No PGRM messages enabled! You must enable one or more in PGRM.h! 57 | #endif 58 | 59 | #ifndef NMEAGPS_DERIVED_TYPES 60 | #error You must "#define NMEAGPS_DERIVED_TYPES" in NMEAGPS_cfg.h! 61 | #endif 62 | 63 | #ifndef NMEAGPS_EXPLICIT_MERGING 64 | #error You must define NMEAGPS_EXPLICIT_MERGING in NMEAGPS_cfg.h 65 | #endif 66 | 67 | #ifdef NMEAGPS_INTERRUPT_PROCESSING 68 | #error You must *NOT* define NMEAGPS_INTERRUPT_PROCESSING in NMEAGPS_cfg.h! 69 | #endif 70 | 71 | //------------------------------------------------------------ 72 | 73 | static GarminNMEA gps; // This parses received characters 74 | static gps_fix fix; 75 | 76 | //---------------------------------------------------------------- 77 | 78 | static void doSomeWork() 79 | { 80 | // Print leap seconds, when it finally arrives. 81 | static bool leapSecondsPrinted = false; 82 | if (not leapSecondsPrinted and (GPSTime::leap_seconds != 0)) { 83 | leapSecondsPrinted = true; 84 | DEBUG_PORT.print( F("GPS leap seconds = ") ); 85 | DEBUG_PORT.println( GPSTime::leap_seconds ); 86 | } 87 | 88 | // Print all the things! 89 | trace_all( DEBUG_PORT, gps, fix ); 90 | 91 | } // doSomeWork 92 | 93 | //------------------------------------ 94 | 95 | static void GPSloop() 96 | { 97 | while (gps.available( gpsPort )) { 98 | fix = gps.read(); 99 | 100 | doSomeWork(); 101 | } 102 | } // GPSloop 103 | 104 | //-------------------------- 105 | 106 | void setup() 107 | { 108 | DEBUG_PORT.begin(9600); 109 | while (!DEBUG_PORT) 110 | ; 111 | 112 | DEBUG_PORT.print( F("PGRM: started\n") ); 113 | DEBUG_PORT.print( F("fix object size = ") ); 114 | DEBUG_PORT.println( sizeof(gps.fix()) ); 115 | DEBUG_PORT.print( F("GarminNMEA object size = ") ); 116 | DEBUG_PORT.println( sizeof(gps) ); 117 | DEBUG_PORT.println( F("Looking for GPS device on " GPS_PORT_NAME) ); 118 | 119 | #ifdef GARMINGPS_PARSE_F 120 | if (LAST_SENTENCE_IN_INTERVAL != (NMEAGPS::nmea_msg_t) GarminNMEA::PGRMF) { 121 | DEBUG_PORT.println( F("ERROR! LAST_SENTENCE_IN_INTERVAL should be PGRMF") ); 122 | for(;;); 123 | } 124 | #endif 125 | 126 | trace_header( DEBUG_PORT ); 127 | DEBUG_PORT.flush(); 128 | 129 | gpsPort.begin(9600); 130 | 131 | } 132 | 133 | //-------------------------- 134 | 135 | void loop() 136 | { 137 | GPSloop(); 138 | } 139 | -------------------------------------------------------------------------------- /examples/SyncTime/SyncTime.ino: -------------------------------------------------------------------------------- 1 | #include 2 | 3 | //====================================================================== 4 | // Program: SyncTime.ino 5 | // 6 | // Description: This program shows how to update the sub-second 7 | // part of a clock's seconds. You can adjust the clock update 8 | // interval to be as small as 9ms. It will calculate the 9 | // correct ms offset from each GPS second. 10 | // 11 | // Prerequisites: 12 | // 1) NMEA.ino works with your device 13 | // 2) GPS_FIX_TIME is enabled in GPSfix_cfg.h 14 | // 3) NMEAGPS_PARSE_RMC is enabled in NMEAGPS_cfg.h. You could use 15 | // any sentence that contains a time field. Be sure to change the 16 | // "if" statement in GPSloop from RMC to your selected sentence. 17 | // 18 | // 'Serial' is for debug output to the Serial Monitor window. 19 | // 20 | // License: 21 | // Copyright (C) 2014-2017, SlashDevin 22 | // 23 | // This file is part of NeoGPS 24 | // 25 | // NeoGPS is free software: you can redistribute it and/or modify 26 | // it under the terms of the GNU General Public License as published by 27 | // the Free Software Foundation, either version 3 of the License, or 28 | // (at your option) any later version. 29 | // 30 | // NeoGPS is distributed in the hope that it will be useful, 31 | // but WITHOUT ANY WARRANTY; without even the implied warranty of 32 | // MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the 33 | // GNU General Public License for more details. 34 | // 35 | // You should have received a copy of the GNU General Public License 36 | // along with NeoGPS. If not, see . 37 | // 38 | //====================================================================== 39 | 40 | #include 41 | 42 | static NMEAGPS gps; 43 | static gps_fix fix; 44 | 45 | #if !defined(GPS_FIX_TIME) 46 | #error You must define GPS_FIX_TIME in GPSfix_cfg.h! 47 | #endif 48 | 49 | #if !defined(NMEAGPS_PARSE_RMC) & \ 50 | !defined(NMEAGPS_PARSE_GLL) & \ 51 | !defined(NMEAGPS_PARSE_GGA) & \ 52 | !defined(NMEAGPS_PARSE_GST) 53 | #error You must define NMEAGPS_PARSE_RMC, GLL, GGA or GST in NMEAGPS_cfg.h! 54 | #endif 55 | 56 | #if !defined(NMEAGPS_TIMESTAMP_FROM_INTERVAL) & \ 57 | !defined(NMEAGPS_TIMESTAMP_FROM_PPS) 58 | #error You must define NMEAGPS_TIMESTAMP_FROM_INTERVAL or PPS in NMEAGPS_cfg.h! 59 | #endif 60 | 61 | #if defined(NMEAGPS_TIMESTAMP_FROM_PPS) 62 | #warning You must modify this sketch to call gps.UTCsecondStart at the PPS rising edge (see NMEAGPS.h comments). 63 | #endif 64 | 65 | #ifdef NMEAGPS_INTERRUPT_PROCESSING 66 | #error You must *NOT* define NMEAGPS_INTERRUPT_PROCESSING in NMEAGPS_cfg.h! 67 | #endif 68 | 69 | //---------------------------------------------------------------- 70 | 71 | static const uint32_t CLOCK_INTERVAL_MS = 100UL; 72 | static uint32_t lastShowTime = CLOCK_INTERVAL_MS+1; // First time never matches 73 | 74 | //---------------------------------------------------------------- 75 | 76 | static void showTime( uint16_t subs, uint16_t factor = 100 /* hundredths */ ) 77 | { 78 | uint8_t showSeconds = fix.dateTime.seconds; 79 | 80 | // Step by seconds until we're in the current UTC second 81 | while (subs >= 1000UL) { 82 | subs -= 1000UL; 83 | if (showSeconds < 59) 84 | showSeconds++; 85 | else 86 | showSeconds = 0; 87 | //DEBUG_PORT.print( '+' ); 88 | } 89 | 90 | DEBUG_PORT.print( showSeconds ); 91 | DEBUG_PORT.print( '.' ); 92 | 93 | // Leading zeroes 94 | for (;;) { 95 | factor /= 10; 96 | if ((factor < 10) || (subs >= factor)) 97 | break; 98 | DEBUG_PORT.print( '0' ); 99 | } 100 | 101 | DEBUG_PORT.println( subs ); 102 | 103 | } // showTime 104 | 105 | //-------------------------- 106 | 107 | void setup() 108 | { 109 | DEBUG_PORT.begin(9600); 110 | while (!DEBUG_PORT) 111 | ; 112 | 113 | DEBUG_PORT.print( F("SyncTime.INO: started\n") ); 114 | DEBUG_PORT.println( F("Looking for GPS device on " GPS_PORT_NAME) ); 115 | DEBUG_PORT.println( F("Local time seconds.milliseconds") ); 116 | DEBUG_PORT.flush(); 117 | 118 | gpsPort.begin( 9600 ); 119 | } 120 | 121 | //-------------------------- 122 | 123 | void loop() 124 | { 125 | while (gps.available( gpsPort )) { 126 | fix = gps.read(); 127 | } 128 | 129 | if (fix.valid.time) { 130 | uint32_t UTCms = gps.UTCms(); 131 | 132 | if (((UTCms % CLOCK_INTERVAL_MS) == 0) && (UTCms != lastShowTime)) { 133 | showTime( UTCms, 1000 ); 134 | lastShowTime = UTCms; 135 | } 136 | } 137 | } 138 | -------------------------------------------------------------------------------- /src/Location.h: -------------------------------------------------------------------------------- 1 | #ifndef NEOGPS_LOCATION_H 2 | #define NEOGPS_LOCATION_H 3 | 4 | #include "NeoGPS_cfg.h" 5 | 6 | // Copyright (C) 2014-2017, SlashDevin 7 | // 8 | // This file is part of NeoGPS 9 | // 10 | // NeoGPS is free software: you can redistribute it and/or modify 11 | // it under the terms of the GNU General Public License as published by 12 | // the Free Software Foundation, either version 3 of the License, or 13 | // (at your option) any later version. 14 | // 15 | // NeoGPS is distributed in the hope that it will be useful, 16 | // but WITHOUT ANY WARRANTY; without even the implied warranty of 17 | // MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the 18 | // GNU General Public License for more details. 19 | // 20 | // You should have received a copy of the GNU General Public License 21 | // along with NeoGPS. If not, see . 22 | 23 | class NMEAGPS; 24 | 25 | namespace NeoGPS { 26 | 27 | class Location_t 28 | { 29 | public: 30 | CONST_CLASS_DATA float LOC_SCALE = 1.0e-7; 31 | 32 | Location_t() {} 33 | Location_t( int32_t lat, int32_t lon ) 34 | : _lat(lat), _lon(lon) 35 | {} 36 | Location_t( float lat, float lon ) 37 | : _lat(lat / LOC_SCALE), _lon(lon / LOC_SCALE) 38 | {} 39 | Location_t( double lat, double lon ) 40 | : _lat(lat / LOC_SCALE), _lon(lon / LOC_SCALE) 41 | {} 42 | 43 | int32_t lat() const { return _lat; }; 44 | void lat( int32_t l ) { _lat = l; }; 45 | float latF() const { return ((float) lat()) * LOC_SCALE; }; 46 | void latF( float v ) { _lat = v / LOC_SCALE; }; 47 | 48 | int32_t lon() const { return _lon; }; 49 | void lon( int32_t l ) { _lon = l; }; 50 | float lonF() const { return ((float) lon()) * LOC_SCALE; }; 51 | void lonF( float v ) { _lon = v / LOC_SCALE; }; 52 | 53 | void init() { _lat = _lon = 0; }; 54 | 55 | CONST_CLASS_DATA float EARTH_RADIUS_KM = 6371.0088; 56 | CONST_CLASS_DATA float RAD_PER_DEG = PI / 180.0; 57 | CONST_CLASS_DATA float DEG_PER_RAD = 180.0 / PI; 58 | CONST_CLASS_DATA float MI_PER_KM = 0.621371; 59 | 60 | //----------------------------------- 61 | // Distance calculations 62 | 63 | static float DistanceKm( const Location_t & p1, const Location_t & p2 ) 64 | { 65 | return DistanceRadians( p1, p2 ) * EARTH_RADIUS_KM; 66 | } 67 | float DistanceKm( const Location_t & p2 ) const 68 | { return DistanceKm( *this, p2 ); } 69 | 70 | static float DistanceMiles( const Location_t & p1, const Location_t & p2 ) 71 | { 72 | return DistanceRadians( p1, p2 ) * EARTH_RADIUS_KM * MI_PER_KM; 73 | } 74 | float DistanceMiles( const Location_t & p2 ) const 75 | { return DistanceMiles( *this, p2 ); } 76 | 77 | static float DistanceRadians( const Location_t & p1, const Location_t & p2 ); 78 | float DistanceRadians( const Location_t & p2 ) const 79 | { return DistanceRadians( *this, p2 ); } 80 | 81 | static float EquirectDistanceRadians 82 | ( const Location_t & p1, const Location_t & p2 ); 83 | float EquirectDistanceRadians( const Location_t & p2 ) const 84 | { return EquirectDistanceRadians( *this, p2 ); } 85 | 86 | static float EquirectDistanceKm( const Location_t & p1, const Location_t & p2 ) 87 | { 88 | return EquirectDistanceRadians( p1, p2 ) * EARTH_RADIUS_KM; 89 | } 90 | float EquirectDistanceKm( const Location_t & p2 ) const 91 | { return EquirectDistanceKm( *this, p2 ); } 92 | 93 | static float EquirectDistanceMiles( const Location_t & p1, const Location_t & p2 ) 94 | { 95 | return EquirectDistanceRadians( p1, p2 ) * EARTH_RADIUS_KM * MI_PER_KM; 96 | } 97 | float EquirectDistanceMiles( const Location_t & p2 ) const 98 | { return EquirectDistanceMiles( *this, p2 ); } 99 | 100 | //----------------------------------- 101 | // Bearing calculations 102 | 103 | static float BearingTo( const Location_t & p1, const Location_t & p2 ); // radians 104 | float BearingTo( const Location_t & p2 ) const // radians 105 | { return BearingTo( *this, p2 ); } 106 | 107 | static float BearingToDegrees( const Location_t & p1, const Location_t & p2 ) 108 | { return BearingTo( p1, p2 ) * DEG_PER_RAD; } 109 | float BearingToDegrees( const Location_t & p2 ) const // radians 110 | { return BearingToDegrees( *this, p2 ); } 111 | 112 | //----------------------------------- 113 | // Offset a location (note distance is in radians, not degrees) 114 | void OffsetBy( float distR, float bearingR ); 115 | 116 | //private: //--------------------------------------- 117 | friend class NMEAGPS; // This does not work?!? 118 | 119 | int32_t _lat; // degrees * 1e7, negative is South 120 | int32_t _lon; // degrees * 1e7, negative is West 121 | 122 | } NEOGPS_PACKED; 123 | 124 | } // NeoGPS 125 | 126 | #endif -------------------------------------------------------------------------------- /src/NeoGPS_cfg.h: -------------------------------------------------------------------------------- 1 | #ifndef NEOGPS_CFG 2 | #define NEOGPS_CFG 3 | 4 | // Copyright (C) 2014-2017, SlashDevin 5 | // 6 | // This file is part of NeoGPS 7 | // 8 | // NeoGPS is free software: you can redistribute it and/or modify 9 | // it under the terms of the GNU General Public License as published by 10 | // the Free Software Foundation, either version 3 of the License, or 11 | // (at your option) any later version. 12 | // 13 | // NeoGPS is distributed in the hope that it will be useful, 14 | // but WITHOUT ANY WARRANTY; without even the implied warranty of 15 | // MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the 16 | // GNU General Public License for more details. 17 | // 18 | // You should have received a copy of the GNU General Public License 19 | // along with NeoGPS. If not, see . 20 | 21 | //------------------------------------------------------------------------ 22 | // Enable/disable packed data structures. 23 | // 24 | // Enabling packed data structures will use two less-portable language 25 | // features of GCC to reduce RAM requirements. Although it was expected to slightly increase execution time and code size, the reverse is true on 8-bit AVRs: the code is smaller and faster with packing enabled. 26 | // 27 | // Disabling packed data structures will be very portable to other 28 | // platforms. NeoGPS configurations will use slightly more RAM, and on 29 | // 8-bit AVRs, the speed is slightly slower, and the code is slightly 30 | // larger. There may be no choice but to disable packing on processors 31 | // that do not support packed structures. 32 | // 33 | // There may also be compiler-specific switches that affect packing and the 34 | // code which accesses packed members. YMMV. 35 | 36 | #include 37 | 38 | #ifdef __AVR__ 39 | #define NEOGPS_PACKED_DATA 40 | #endif 41 | 42 | //------------------------------------------------------------------------ 43 | // Based on the above define, choose which set of packing macros should 44 | // be used in the rest of the NeoGPS package. Do not change these defines. 45 | 46 | #ifdef NEOGPS_PACKED_DATA 47 | 48 | // This is for specifying the number of bits to be used for a 49 | // member of a struct. Booleans are typically one bit. 50 | #define NEOGPS_BF(b) :b 51 | 52 | // This is for requesting the compiler to pack the struct or class members 53 | // "as closely as possible". This is a compiler-dependent interpretation. 54 | #define NEOGPS_PACKED __attribute__((packed)) 55 | 56 | #else 57 | 58 | // Let the compiler do whatever it wants. 59 | 60 | #define NEOGPS_PACKED 61 | #define NEOGPS_BF(b) 62 | 63 | #endif 64 | 65 | //------------------------------------------------------------------------ 66 | // Accommodate C++ compiler and IDE changes. 67 | // 68 | // Declaring constants as class data instead of instance data helps avoid 69 | // collisions with #define names, and allows the compiler to perform more 70 | // checks on their usage. 71 | // 72 | // Until C++ 10 and IDE 1.6.8, initialized class data constants 73 | // were declared like this: 74 | // 75 | // static const = ; 76 | // 77 | // Now, non-simple types (e.g., float) must be declared as 78 | // 79 | // static constexpr = ; 80 | // 81 | // The good news is that this allows the compiler to optimize out an 82 | // expression that is "promised" to be "evaluatable" as a constant. 83 | // The bad news is that it introduces a new language keyword, and the old 84 | // code raises an error. 85 | // 86 | // TODO: Evaluate the requirement for the "static" keyword. 87 | // TODO: Evaluate using a C++ version preprocessor symbol for the #if. 88 | // #if __cplusplus >= 201103L (from XBee.h) 89 | // 90 | // The CONST_CLASS_DATA define will expand to the appropriate keywords. 91 | // 92 | 93 | 94 | #if ( \ 95 | (ARDUINO < 10606) | \ 96 | ((10700 <= ARDUINO) & (ARDUINO <= 10799 )) | \ 97 | ((107000 <= ARDUINO) & (ARDUINO <= 107999)) \ 98 | ) \ 99 | & \ 100 | !defined(ESP8266) // PlatformIO Pull Request #82 101 | 102 | #define CONST_CLASS_DATA static const 103 | 104 | #else 105 | 106 | #define CONST_CLASS_DATA static constexpr 107 | 108 | #endif 109 | 110 | //------------------------------------------------------------------------ 111 | // The PROGMEM definitions are not correct for Zero, MKR1000 and 112 | // earlier versions of Teensy boards 113 | 114 | #if defined(ARDUINO_SAMD_MKRZERO) | \ 115 | defined(ARDUINO_SAMD_ZERO) | \ 116 | defined(ARDUINO_SAM_DUE) | \ 117 | defined(ARDUINO_ARCH_ARC32) | \ 118 | defined(__TC27XX__) | \ 119 | (defined(TEENSYDUINO) && (TEENSYDUINO < 139)) 120 | #undef pgm_read_ptr 121 | #define pgm_read_ptr(addr) (*(const void **)(addr)) 122 | #endif 123 | 124 | 125 | #endif 126 | -------------------------------------------------------------------------------- /src/Location.cpp: -------------------------------------------------------------------------------- 1 | // Copyright (C) 2014-2017, SlashDevin 2 | // 3 | // This file is part of NeoGPS 4 | // 5 | // NeoGPS is free software: you can redistribute it and/or modify 6 | // it under the terms of the GNU General Public License as published by 7 | // the Free Software Foundation, either version 3 of the License, or 8 | // (at your option) any later version. 9 | // 10 | // NeoGPS is distributed in the hope that it will be useful, 11 | // but WITHOUT ANY WARRANTY; without even the implied warranty of 12 | // MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the 13 | // GNU General Public License for more details. 14 | // 15 | // You should have received a copy of the GNU General Public License 16 | // along with NeoGPS. If not, see . 17 | 18 | #include "Location.h" 19 | 20 | using namespace NeoGPS; 21 | 22 | //--------------------------------------------------------------------- 23 | // Calculate dLon with integers, less one bit to avoid overflow 24 | // (360 * 1e7 = 3600000000, which is too big). 25 | // Retains precision when points are close together. 26 | 27 | int32_t safeDLon( int32_t p2, int32_t p1 ) 28 | { 29 | int32_t dLonL; 30 | int32_t halfDLon = (p2/2 - p1/2); 31 | if (halfDLon < -1800000000L/2) { 32 | dLonL = (p2 + 1800000000L) - (p1 - 1800000000L); 33 | } else if (1800000000L/2 < halfDLon) { 34 | dLonL = (p2 - 1800000000L) - (p1 + 1800000000L); 35 | } else { 36 | dLonL = p2 - p1; 37 | } 38 | return dLonL; 39 | 40 | } // safeDLon 41 | 42 | //--------------------------------------------------------------------- 43 | 44 | float Location_t::DistanceRadians 45 | ( const Location_t & p1, const Location_t & p2 ) 46 | { 47 | int32_t dLonL = safeDLon( p2.lon(), p1.lon() ); 48 | int32_t dLatL = p2.lat() - p1.lat(); 49 | 50 | if ((abs(dLatL)+abs(dLonL)) < 1000) { 51 | // VERY close together. Just use equirect approximation with precise integers. 52 | // This is not needed for accuracy (that I can measure), but it is 53 | // a quicker calculation. 54 | return EquirectDistanceRadians( p1, p2 ); 55 | } 56 | 57 | // Haversine calculation from http://www.movable-type.co.uk/scripts/latlong.html 58 | float dLat = dLatL * RAD_PER_DEG * LOC_SCALE; 59 | float haverDLat = sin(dLat/2.0); 60 | haverDLat *= haverDLat; // squared 61 | 62 | float dLon = dLonL * RAD_PER_DEG * LOC_SCALE; 63 | float haverDLon = sin(dLon/2.0); 64 | haverDLon *= haverDLon; // squared 65 | 66 | float lat1 = p1.latF(); 67 | lat1 *= RAD_PER_DEG; 68 | float lat2 = p2.latF(); 69 | lat2 *= RAD_PER_DEG; 70 | float a = haverDLat + cos(lat1) * cos(lat2) * haverDLon; 71 | 72 | float c = 2 * atan2( sqrt(a), sqrt(1-a) ); 73 | 74 | return c; 75 | 76 | } // DistanceRadians 77 | 78 | //--------------------------------------------------------------------- 79 | 80 | float Location_t::EquirectDistanceRadians 81 | ( const Location_t & p1, const Location_t & p2 ) 82 | { 83 | // Equirectangular calculation from http://www.movable-type.co.uk/scripts/latlong.html 84 | 85 | float dLat = (p2.lat() - p1.lat()) * RAD_PER_DEG * LOC_SCALE; 86 | float dLon = safeDLon( p2.lon(), p1.lon() ) * RAD_PER_DEG * LOC_SCALE; 87 | float x = dLon * cos( p1.lat() * RAD_PER_DEG * LOC_SCALE + dLat/2 ); 88 | return sqrt( x*x + dLat*dLat ); 89 | 90 | } // EquirectDistanceRadians 91 | 92 | //--------------------------------------------------------------------- 93 | 94 | float Location_t::BearingTo( const Location_t & p1, const Location_t & p2 ) 95 | { 96 | int32_t dLonL = safeDLon( p2.lon(), p1.lon() ); 97 | float dLon = dLonL * RAD_PER_DEG * LOC_SCALE; 98 | int32_t dLatL = p2.lat() - p1.lat(); 99 | float lat1 = p1.lat() * RAD_PER_DEG * LOC_SCALE; 100 | float cosLat1 = cos( lat1 ); 101 | float x, y, bearing; 102 | 103 | if ((abs(dLatL)+abs(dLonL)) < 1000) { 104 | // VERY close together. Just use equirect approximation with precise integers. 105 | x = dLonL * cosLat1; 106 | y = dLatL; 107 | bearing = PI/2.0 - atan2(y, x); 108 | 109 | } else { 110 | float lat2 = p2.lat() * RAD_PER_DEG * LOC_SCALE; 111 | float cosLat2 = cos(lat2); 112 | y = sin(dLon) * cosLat2; 113 | x = cosLat1 * sin(lat2) - sin(lat1) * cosLat2 * cos(dLon); 114 | bearing = atan2(y, x); 115 | } 116 | 117 | if (bearing < 0.0) 118 | bearing += TWO_PI; 119 | 120 | return bearing; 121 | 122 | } // BearingTo 123 | 124 | //--------------------------------------------------------------------- 125 | 126 | void Location_t::OffsetBy( float distR, float bearingR ) 127 | { 128 | float lat1 = lat() * RAD_PER_DEG * LOC_SCALE; 129 | float newLat = asin( sin(lat1)*cos(distR) + 130 | cos(lat1)*sin(distR)*cos(bearingR) ); 131 | float dLon = atan2( sin(bearingR)*sin(distR)*cos(lat1), 132 | cos(distR)-sin(lat1)*sin(newLat)); 133 | 134 | _lat = (newLat / (RAD_PER_DEG * LOC_SCALE)); 135 | _lon += (dLon / (RAD_PER_DEG * LOC_SCALE)); 136 | 137 | } // OffsetBy -------------------------------------------------------------------------------- /examples/PUBX/PUBX.ino: -------------------------------------------------------------------------------- 1 | #include 2 | #include 3 | 4 | //====================================================================== 5 | // Program: PUBX.ino 6 | // 7 | // Description: This program parses NMEA proprietary messages from 8 | // ublox devices. It is an extension of NMEA.ino. 9 | // 10 | // Prerequisites: 11 | // 1) You have a ublox GPS device 12 | // 2) NMEA.ino works with your device 13 | // 3) You have installed ubxNMEA.H and ubxNMEA.CPP 14 | // 4) At least one NMEA standard or proprietary sentence has been enabled. 15 | // 5) Implicit Merging is disabled. 16 | // 17 | // Serial is for debug output to the Serial Monitor window. 18 | // 19 | // License: 20 | // Copyright (C) 2014-2017, SlashDevin 21 | // 22 | // This file is part of NeoGPS 23 | // 24 | // NeoGPS is free software: you can redistribute it and/or modify 25 | // it under the terms of the GNU General Public License as published by 26 | // the Free Software Foundation, either version 3 of the License, or 27 | // (at your option) any later version. 28 | // 29 | // NeoGPS is distributed in the hope that it will be useful, 30 | // but WITHOUT ANY WARRANTY; without even the implied warranty of 31 | // MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the 32 | // GNU General Public License for more details. 33 | // 34 | // You should have received a copy of the GNU General Public License 35 | // along with NeoGPS. If not, see . 36 | // 37 | //====================================================================== 38 | 39 | #include 40 | 41 | #include 42 | 43 | //------------------------------------------------------------ 44 | // Check that the config files are set up properly 45 | 46 | #if !defined( NMEAGPS_PARSE_GGA ) & !defined( NMEAGPS_PARSE_GLL ) & \ 47 | !defined( NMEAGPS_PARSE_GSA ) & !defined( NMEAGPS_PARSE_GSV ) & \ 48 | !defined( NMEAGPS_PARSE_RMC ) & !defined( NMEAGPS_PARSE_VTG ) & \ 49 | !defined( NMEAGPS_PARSE_ZDA ) & !defined( NMEAGPS_PARSE_GST ) & \ 50 | !defined( NMEAGPS_PARSE_PUBX_00 ) & !defined( NMEAGPS_PARSE_PUBX_04 ) 51 | 52 | #error No NMEA sentences enabled: no fix data available. 53 | 54 | #endif 55 | 56 | #if !defined( NMEAGPS_PARSE_PUBX_00 ) & !defined( NMEAGPS_PARSE_PUBX_04 ) 57 | #error No PUBX messages enabled! You must enable one or more in PUBX_cfg.h! 58 | #endif 59 | 60 | #ifndef NMEAGPS_DERIVED_TYPES 61 | #error You must "#define NMEAGPS_DERIVED_TYPES" in NMEAGPS_cfg.h! 62 | #endif 63 | 64 | #ifndef NMEAGPS_EXPLICIT_MERGING 65 | #error You must define NMEAGPS_EXPLICIT_MERGING in NMEAGPS_cfg.h 66 | #endif 67 | 68 | #ifdef NMEAGPS_INTERRUPT_PROCESSING 69 | #error You must *NOT* define NMEAGPS_INTERRUPT_PROCESSING in NMEAGPS_cfg.h! 70 | #endif 71 | 72 | //------------------------------------------------------------ 73 | 74 | static ubloxNMEA gps; // This parses received characters 75 | static gps_fix fix; 76 | 77 | //---------------------------------------------------------------- 78 | 79 | static void poll() 80 | { 81 | #if defined( NMEAGPS_PARSE_PUBX_00 ) 82 | gps.send_P( &gpsPort, F("PUBX,00") ); 83 | #endif 84 | #if defined( NMEAGPS_PARSE_PUBX_04 ) 85 | gps.send_P( &gpsPort, F("PUBX,04") ); 86 | #endif 87 | } 88 | 89 | //---------------------------------------------------------------- 90 | 91 | static void doSomeWork() 92 | { 93 | // Print all the things! 94 | trace_all( DEBUG_PORT, gps, fix ); 95 | 96 | // Ask for the proprietary messages again 97 | poll(); 98 | 99 | } // doSomeWork 100 | 101 | //------------------------------------ 102 | 103 | static void GPSloop() 104 | { 105 | while (gps.available( gpsPort )) { 106 | fix = gps.read(); 107 | 108 | #if defined(GPS_FIX_VELNED) && defined(NMEAGPS_PARSE_PUBX_00) 109 | fix.calculateNorthAndEastVelocityFromSpeedAndHeading(); 110 | #endif 111 | 112 | doSomeWork(); 113 | } 114 | } // GPSloop 115 | 116 | //-------------------------- 117 | 118 | void setup() 119 | { 120 | DEBUG_PORT.begin(9600); 121 | while (!DEBUG_PORT) 122 | ; 123 | 124 | DEBUG_PORT.print( F("PUBX: started\n") ); 125 | DEBUG_PORT.print( F("fix object size = ") ); 126 | DEBUG_PORT.println( sizeof(gps.fix()) ); 127 | DEBUG_PORT.print( F("ubloxNMEA object size = ") ); 128 | DEBUG_PORT.println( sizeof(gps) ); 129 | DEBUG_PORT.println( F("Looking for GPS device on " GPS_PORT_NAME) ); 130 | 131 | #ifdef NMEAGPS_PARSE_PUBX_04 132 | if (LAST_SENTENCE_IN_INTERVAL != (NMEAGPS::nmea_msg_t) ubloxNMEA::PUBX_04) { 133 | DEBUG_PORT.println( F("ERROR! LAST_SENTENCE_IN_INTERVAL should be PUBX_04") ); 134 | for(;;); 135 | } 136 | #else 137 | if (LAST_SENTENCE_IN_INTERVAL != (NMEAGPS::nmea_msg_t) ubloxNMEA::PUBX_00) { 138 | DEBUG_PORT.println( F("ERROR! LAST_SENTENCE_IN_INTERVAL should be PUBX_00") ); 139 | for(;;); 140 | } 141 | #endif 142 | 143 | trace_header( DEBUG_PORT ); 144 | DEBUG_PORT.flush(); 145 | 146 | gpsPort.begin(9600); 147 | 148 | // Ask for the special PUBX sentences 149 | poll(); 150 | } 151 | 152 | //-------------------------- 153 | 154 | void loop() 155 | { 156 | GPSloop(); 157 | } 158 | -------------------------------------------------------------------------------- /src/NeoTime.cpp: -------------------------------------------------------------------------------- 1 | // Copyright (C) 2014-2017, SlashDevin 2 | // 3 | // This file is part of NeoGPS 4 | // 5 | // NeoGPS is free software: you can redistribute it and/or modify 6 | // it under the terms of the GNU General Public License as published by 7 | // the Free Software Foundation, either version 3 of the License, or 8 | // (at your option) any later version. 9 | // 10 | // NeoGPS is distributed in the hope that it will be useful, 11 | // but WITHOUT ANY WARRANTY; without even the implied warranty of 12 | // MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the 13 | // GNU General Public License for more details. 14 | // 15 | // You should have received a copy of the GNU General Public License 16 | // along with NeoGPS. If not, see . 17 | 18 | #include "NeoTime.h" 19 | 20 | // For strtoul declaration 21 | #include 22 | 23 | #include 24 | 25 | Print & operator<<( Print& outs, const NeoGPS::time_t& t ) 26 | { 27 | outs.print( t.full_year( t.year ) ); 28 | outs.write( '-' ); 29 | if (t.month < 10) outs.write( '0' ); 30 | outs.print( t.month ); 31 | outs.write( '-' ); 32 | if (t.date < 10) outs.write( '0' ); 33 | outs.print( t.date ); 34 | outs.write( ' ' ); 35 | if (t.hours < 10) outs.write( '0' ); 36 | outs.print( t.hours ); 37 | outs.write( ':' ); 38 | if (t.minutes < 10) outs.write( '0' ); 39 | outs.print( t.minutes ); 40 | outs.write( ':' ); 41 | if (t.seconds < 10) outs.write( '0' ); 42 | outs.print( t.seconds ); 43 | 44 | return outs; 45 | } 46 | 47 | using NeoGPS::time_t; 48 | 49 | bool time_t::parse(str_P s) 50 | { 51 | static size_t BUF_MAX = 32; 52 | char buf[BUF_MAX]; 53 | strcpy_P(buf, s); 54 | char* sp = &buf[0]; 55 | uint16_t value = strtoul(sp, &sp, 10); 56 | 57 | if (*sp != '-') return false; 58 | year = value % 100; 59 | if (full_year() != value) return false; 60 | 61 | value = strtoul(sp + 1, &sp, 10); 62 | if (*sp != '-') return false; 63 | month = value; 64 | 65 | value = strtoul(sp + 1, &sp, 10); 66 | if (*sp != ' ') return false; 67 | date = value; 68 | 69 | value = strtoul(sp + 1, &sp, 10); 70 | if (*sp != ':') return false; 71 | hours = value; 72 | 73 | value = strtoul(sp + 1, &sp, 10); 74 | if (*sp != ':') return false; 75 | minutes = value; 76 | 77 | value = strtoul(sp + 1, &sp, 10); 78 | if (*sp != 0) return false; 79 | seconds = value; 80 | 81 | return (is_valid()); 82 | } 83 | 84 | #ifdef TIME_EPOCH_MODIFIABLE 85 | uint16_t time_t::s_epoch_year = Y2K_EPOCH_YEAR; 86 | uint8_t time_t::s_epoch_offset = 0; 87 | uint8_t time_t::s_epoch_weekday = Y2K_EPOCH_WEEKDAY; 88 | uint8_t time_t::s_pivot_year = 0; 89 | #endif 90 | 91 | const uint8_t time_t::days_in[] __PROGMEM = { 92 | 0, 31, 28, 31, 30, 31, 30, 31, 31, 30, 31, 30, 31 93 | }; 94 | 95 | time_t::time_t(clock_t c) 96 | { 97 | uint16_t dayno = c / SECONDS_PER_DAY; 98 | c -= dayno * (uint32_t) SECONDS_PER_DAY; 99 | day = weekday_for(dayno); 100 | 101 | uint16_t y = epoch_year(); 102 | for (;;) { 103 | uint16_t days = days_per( y ); 104 | if (dayno < days) break; 105 | dayno -= days; 106 | y++; 107 | } 108 | bool leap_year = is_leap(y); 109 | y -= epoch_year(); 110 | y += epoch_offset(); 111 | while (y > 100) 112 | y -= 100; 113 | year = y; 114 | 115 | month = 1; 116 | for (;;) { 117 | uint8_t days = pgm_read_byte(&days_in[month]); 118 | if (leap_year && (month == 2)) days++; 119 | if (dayno < days) break; 120 | dayno -= days; 121 | month++; 122 | } 123 | date = dayno + 1; 124 | 125 | hours = c / SECONDS_PER_HOUR; 126 | 127 | uint16_t c_ms; 128 | if (hours < 18) // save 16uS 129 | c_ms = (uint16_t) c - (hours * (uint16_t) SECONDS_PER_HOUR); 130 | else 131 | c_ms = c - (hours * (uint32_t) SECONDS_PER_HOUR); 132 | minutes = c_ms / SECONDS_PER_MINUTE; 133 | seconds = c_ms - (minutes * SECONDS_PER_MINUTE); 134 | } 135 | 136 | void time_t::init() 137 | { 138 | seconds = 139 | hours = 140 | minutes = 0; 141 | date = 1; 142 | month = 1; 143 | year = epoch_year() % 100; 144 | day = epoch_weekday(); 145 | } 146 | 147 | time_t::operator clock_t() const 148 | { 149 | clock_t c = days() * SECONDS_PER_DAY; 150 | if (hours < 18) 151 | c += hours * (uint16_t) SECONDS_PER_HOUR; 152 | else 153 | c += hours * (uint32_t) SECONDS_PER_HOUR; 154 | c += minutes * (uint16_t) SECONDS_PER_MINUTE; 155 | c += seconds; 156 | 157 | return (c); 158 | } 159 | 160 | uint16_t time_t::days() const 161 | { 162 | uint16_t day_count = day_of_year(); 163 | 164 | uint16_t y = full_year(); 165 | while (y-- > epoch_year()) 166 | day_count += days_per(y); 167 | 168 | return (day_count); 169 | } 170 | 171 | uint16_t time_t::day_of_year() const 172 | { 173 | uint16_t dayno = date - 1; 174 | bool leap_year = is_leap(); 175 | 176 | for (uint8_t m = 1; m < month; m++) { 177 | dayno += pgm_read_byte(&days_in[m]); 178 | if (leap_year && (m == 2)) dayno++; 179 | } 180 | 181 | return (dayno); 182 | } 183 | 184 | #ifdef TIME_EPOCH_MODIFIABLE 185 | void time_t::use_fastest_epoch() 186 | { 187 | // Figure out when we were compiled and use the year for a really 188 | // fast epoch_year. Format "MMM DD YYYY" 189 | const char* compile_date = (const char *) PSTR(__DATE__); 190 | uint16_t compile_year = 0; 191 | for (uint8_t i = 7; i < 11; i++) 192 | compile_year = compile_year*10 + (pgm_read_byte(&compile_date[i]) - '0'); 193 | 194 | // Temporarily set a Y2K epoch so we can figure out the day for 195 | // January 1 of this year 196 | epoch_year ( Y2K_EPOCH_YEAR ); 197 | epoch_weekday ( Y2K_EPOCH_WEEKDAY ); 198 | 199 | time_t this_year(0); 200 | this_year.year = compile_year % 100; 201 | this_year.set_day(); 202 | uint8_t compile_weekday = this_year.day; 203 | 204 | epoch_year ( compile_year ); 205 | epoch_weekday( compile_weekday ); 206 | pivot_year ( this_year.year ); 207 | } 208 | #endif -------------------------------------------------------------------------------- /examples/NMEAloc/NMEAloc.ino: -------------------------------------------------------------------------------- 1 | #include 2 | 3 | //====================================================================== 4 | // Program: NMEAloc.ino 5 | // 6 | // Description: This program only parses an RMC sentence for the lat/lon. 7 | // 8 | // Prerequisites: 9 | // 1) NMEA.ino works with your device (correct TX/RX pins and baud rate) 10 | // 2) The RMC sentence has been enabled. 11 | // 3) Your device sends an RMC sentence (e.g., $GPRMC). 12 | // 13 | // 'Serial' is for debug output to the Serial Monitor window. 14 | // 15 | // License: 16 | // Copyright (C) 2014-2017, SlashDevin 17 | // 18 | // This file is part of NeoGPS 19 | // 20 | // NeoGPS is free software: you can redistribute it and/or modify 21 | // it under the terms of the GNU General Public License as published by 22 | // the Free Software Foundation, either version 3 of the License, or 23 | // (at your option) any later version. 24 | // 25 | // NeoGPS is distributed in the hope that it will be useful, 26 | // but WITHOUT ANY WARRANTY; without even the implied warranty of 27 | // MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the 28 | // GNU General Public License for more details. 29 | // 30 | // You should have received a copy of the GNU General Public License 31 | // along with NeoGPS. If not, see . 32 | // 33 | //====================================================================== 34 | 35 | #include 36 | 37 | //------------------------------------------------------------ 38 | // Check that the config files are set up properly 39 | 40 | #if !defined( NMEAGPS_PARSE_RMC ) 41 | #error You must uncomment NMEAGPS_PARSE_RMC in NMEAGPS_cfg.h! 42 | #endif 43 | 44 | #if !defined( GPS_FIX_TIME ) 45 | #error You must uncomment GPS_FIX_TIME in GPSfix_cfg.h! 46 | #endif 47 | 48 | #if !defined( GPS_FIX_LOCATION ) 49 | #error You must uncomment GPS_FIX_LOCATION in GPSfix_cfg.h! 50 | #endif 51 | 52 | #if !defined( GPS_FIX_SPEED ) 53 | #error You must uncomment GPS_FIX_SPEED in GPSfix_cfg.h! 54 | #endif 55 | 56 | #if !defined( GPS_FIX_SATELLITES ) 57 | #error You must uncomment GPS_FIX_SATELLITES in GPSfix_cfg.h! 58 | #endif 59 | 60 | #ifdef NMEAGPS_INTERRUPT_PROCESSING 61 | #error You must *NOT* define NMEAGPS_INTERRUPT_PROCESSING in NMEAGPS_cfg.h! 62 | #endif 63 | 64 | //------------------------------------------------------------ 65 | 66 | static NMEAGPS gps; // This parses the GPS characters 67 | 68 | //---------------------------------------------------------------- 69 | // Print the 32-bit integer degrees *as if* they were high-precision floats 70 | 71 | static void printL( Print & outs, int32_t degE7 ); 72 | static void printL( Print & outs, int32_t degE7 ) 73 | { 74 | // Extract and print negative sign 75 | if (degE7 < 0) { 76 | degE7 = -degE7; 77 | outs.print( '-' ); 78 | } 79 | 80 | // Whole degrees 81 | int32_t deg = degE7 / 10000000L; 82 | outs.print( deg ); 83 | outs.print( '.' ); 84 | 85 | // Get fractional degrees 86 | degE7 -= deg*10000000L; 87 | 88 | // Print leading zeroes, if needed 89 | int32_t factor = 1000000L; 90 | while ((degE7 < factor) && (factor > 1L)){ 91 | outs.print( '0' ); 92 | factor /= 10L; 93 | } 94 | 95 | // Print fractional degrees 96 | outs.print( degE7 ); 97 | } 98 | 99 | static void doSomeWork( const gps_fix & fix ); 100 | static void doSomeWork( const gps_fix & fix ) 101 | { 102 | // This is the best place to do your time-consuming work, right after 103 | // the RMC sentence was received. If you do anything in "loop()", 104 | // you could cause GPS characters to be lost, and you will not 105 | // get a good lat/lon. 106 | // For this example, we just print the lat/lon. If you print too much, 107 | // this routine will not get back to "loop()" in time to process 108 | // the next set of GPS data. 109 | 110 | if (fix.valid.location) { 111 | 112 | if ( fix.dateTime.seconds < 10 ) 113 | DEBUG_PORT.print( '0' ); 114 | DEBUG_PORT.print( fix.dateTime.seconds ); 115 | DEBUG_PORT.print( ',' ); 116 | 117 | // DEBUG_PORT.print( fix.latitude(), 6 ); // floating-point display 118 | // DEBUG_PORT.print( fix.latitudeL() ); // integer display 119 | printL( DEBUG_PORT, fix.latitudeL() ); // prints int like a float 120 | DEBUG_PORT.print( ',' ); 121 | // DEBUG_PORT.print( fix.longitude(), 6 ); // floating-point display 122 | // DEBUG_PORT.print( fix.longitudeL() ); // integer display 123 | printL( DEBUG_PORT, fix.longitudeL() ); // prints int like a float 124 | 125 | DEBUG_PORT.print( ',' ); 126 | if (fix.valid.satellites) 127 | DEBUG_PORT.print( fix.satellites ); 128 | 129 | DEBUG_PORT.print( ',' ); 130 | DEBUG_PORT.print( fix.speed(), 6 ); 131 | DEBUG_PORT.print( F(" kn = ") ); 132 | DEBUG_PORT.print( fix.speed_mph(), 6 ); 133 | DEBUG_PORT.print( F(" mph") ); 134 | 135 | } else { 136 | // No valid location data yet! 137 | DEBUG_PORT.print( '?' ); 138 | } 139 | 140 | DEBUG_PORT.println(); 141 | 142 | } // doSomeWork 143 | 144 | //------------------------------------ 145 | 146 | static void GPSloop(); 147 | static void GPSloop() 148 | { 149 | while (gps.available( gpsPort )) 150 | doSomeWork( gps.read() ); 151 | 152 | } // GPSloop 153 | 154 | //-------------------------- 155 | 156 | void setup() 157 | { 158 | DEBUG_PORT.begin(9600); 159 | while (!DEBUG_PORT) 160 | ; 161 | 162 | DEBUG_PORT.print( F("NMEAloc.INO: started\n") ); 163 | DEBUG_PORT.print( F("fix object size = ") ); 164 | DEBUG_PORT.println( sizeof(gps.fix()) ); 165 | DEBUG_PORT.print( F("NMEAGPS object size = ") ); 166 | DEBUG_PORT.println( sizeof(gps) ); 167 | DEBUG_PORT.println( F("Looking for GPS device on " GPS_PORT_NAME) ); 168 | 169 | #ifdef NMEAGPS_NO_MERGING 170 | DEBUG_PORT.println( F("Only displaying data from xxRMC sentences.\n Other sentences may be parsed, but their data will not be displayed.") ); 171 | #endif 172 | 173 | DEBUG_PORT.flush(); 174 | 175 | gpsPort.begin(9600); 176 | } 177 | 178 | //-------------------------- 179 | 180 | void loop() 181 | { 182 | GPSloop(); 183 | } 184 | -------------------------------------------------------------------------------- /examples/NMEAtimezone/NMEAtimezone.ino: -------------------------------------------------------------------------------- 1 | #include 2 | 3 | //====================================================================== 4 | // Program: NMEAtimezone.ino 5 | // 6 | // Description: This program shows how to offset the GPS dateTime member 7 | // into your specific timezone. GPS devices do not know which 8 | // timezone they are in, so they always report a UTC time. This 9 | // is the same as GMT. 10 | // 11 | // Prerequisites: 12 | // 1) NMEA.ino works with your device 13 | // 2) GPS_FIX_TIME is enabled in GPSfix_cfg.h 14 | // 3) NMEAGPS_PARSE_RMC is enabled in NMEAGPS_cfg.h. You could use 15 | // any sentence that contains a time field. Be sure to change the 16 | // "if" statement in GPSloop from RMC to your selected sentence. 17 | // 18 | // 'Serial' is for debug output to the Serial Monitor window. 19 | // 20 | // License: 21 | // Copyright (C) 2014-2017, SlashDevin 22 | // 23 | // This file is part of NeoGPS 24 | // 25 | // NeoGPS is free software: you can redistribute it and/or modify 26 | // it under the terms of the GNU General Public License as published by 27 | // the Free Software Foundation, either version 3 of the License, or 28 | // (at your option) any later version. 29 | // 30 | // NeoGPS is distributed in the hope that it will be useful, 31 | // but WITHOUT ANY WARRANTY; without even the implied warranty of 32 | // MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the 33 | // GNU General Public License for more details. 34 | // 35 | // You should have received a copy of the GNU General Public License 36 | // along with NeoGPS. If not, see . 37 | // 38 | //====================================================================== 39 | 40 | static NMEAGPS gps; // This parses received characters 41 | static gps_fix fix; // This contains all the parsed pieces 42 | 43 | //-------------------------- 44 | // CHECK CONFIGURATION 45 | 46 | #if !defined(GPS_FIX_TIME) | !defined(GPS_FIX_DATE) 47 | #error You must define GPS_FIX_TIME and DATE in GPSfix_cfg.h! 48 | #endif 49 | 50 | #if !defined(NMEAGPS_PARSE_RMC) & !defined(NMEAGPS_PARSE_ZDA) 51 | #error You must define NMEAGPS_PARSE_RMC or ZDA in NMEAGPS_cfg.h! 52 | #endif 53 | 54 | #include 55 | 56 | //-------------------------- 57 | // Set these values to the offset of your timezone from GMT 58 | 59 | static const int32_t zone_hours = -5L; // EST 60 | static const int32_t zone_minutes = 0L; // usually zero 61 | static const NeoGPS::clock_t zone_offset = 62 | zone_hours * NeoGPS::SECONDS_PER_HOUR + 63 | zone_minutes * NeoGPS::SECONDS_PER_MINUTE; 64 | 65 | // Uncomment one DST changeover rule, or define your own: 66 | #define USA_DST 67 | //#define EU_DST 68 | 69 | #if defined(USA_DST) 70 | static const uint8_t springMonth = 3; 71 | static const uint8_t springDate = 14; // latest 2nd Sunday 72 | static const uint8_t springHour = 2; 73 | static const uint8_t fallMonth = 11; 74 | static const uint8_t fallDate = 7; // latest 1st Sunday 75 | static const uint8_t fallHour = 2; 76 | #define CALCULATE_DST 77 | 78 | #elif defined(EU_DST) 79 | static const uint8_t springMonth = 3; 80 | static const uint8_t springDate = 31; // latest last Sunday 81 | static const uint8_t springHour = 1; 82 | static const uint8_t fallMonth = 10; 83 | static const uint8_t fallDate = 31; // latest last Sunday 84 | static const uint8_t fallHour = 1; 85 | #define CALCULATE_DST 86 | #endif 87 | 88 | //-------------------------- 89 | 90 | void adjustTime( NeoGPS::time_t & dt ) 91 | { 92 | NeoGPS::clock_t seconds = dt; // convert date/time structure to seconds 93 | 94 | #ifdef CALCULATE_DST 95 | // Calculate DST changeover times once per reset and year! 96 | static NeoGPS::time_t changeover; 97 | static NeoGPS::clock_t springForward, fallBack; 98 | 99 | if ((springForward == 0) || (changeover.year != dt.year)) { 100 | 101 | // Calculate the spring changeover time (seconds) 102 | changeover.year = dt.year; 103 | changeover.month = springMonth; 104 | changeover.date = springDate; 105 | changeover.hours = springHour; 106 | changeover.minutes = 0; 107 | changeover.seconds = 0; 108 | changeover.set_day(); 109 | // Step back to a Sunday, if day != SUNDAY 110 | changeover.date -= (changeover.day - NeoGPS::time_t::SUNDAY); 111 | springForward = (NeoGPS::clock_t) changeover; 112 | 113 | // Calculate the fall changeover time (seconds) 114 | changeover.month = fallMonth; 115 | changeover.date = fallDate; 116 | changeover.hours = fallHour - 1; // to account for the "apparent" DST +1 117 | changeover.set_day(); 118 | // Step back to a Sunday, if day != SUNDAY 119 | changeover.date -= (changeover.day - NeoGPS::time_t::SUNDAY); 120 | fallBack = (NeoGPS::clock_t) changeover; 121 | } 122 | #endif 123 | 124 | // First, offset from UTC to the local timezone 125 | seconds += zone_offset; 126 | 127 | #ifdef CALCULATE_DST 128 | // Then add an hour if DST is in effect 129 | if ((springForward <= seconds) && (seconds < fallBack)) 130 | seconds += NeoGPS::SECONDS_PER_HOUR; 131 | #endif 132 | 133 | dt = seconds; // convert seconds back to a date/time structure 134 | 135 | } // adjustTime 136 | 137 | //-------------------------- 138 | 139 | static void GPSloop() 140 | { 141 | while (gps.available( gpsPort )) { 142 | fix = gps.read(); 143 | // Display the local time 144 | 145 | if (fix.valid.time && fix.valid.date) { 146 | adjustTime( fix.dateTime ); 147 | 148 | DEBUG_PORT << fix.dateTime; 149 | } 150 | DEBUG_PORT.println(); 151 | } 152 | 153 | } // GPSloop 154 | 155 | //-------------------------- 156 | 157 | #ifdef NMEAGPS_INTERRUPT_PROCESSING 158 | static void GPSisr( uint8_t c ) 159 | { 160 | gps.handle( c ); 161 | } 162 | #endif 163 | 164 | //-------------------------- 165 | 166 | void setup() 167 | { 168 | DEBUG_PORT.begin(9600); 169 | while (!DEBUG_PORT) 170 | ; 171 | 172 | DEBUG_PORT.print( F("NMEAtimezone.INO: started\n") ); 173 | DEBUG_PORT.println( F("Looking for GPS device on " GPS_PORT_NAME ) ); 174 | DEBUG_PORT.println( F("Local time") ); 175 | DEBUG_PORT.flush(); 176 | 177 | gpsPort.begin( 9600 ); 178 | #ifdef NMEAGPS_INTERRUPT_PROCESSING 179 | gpsPort.attachInterrupt( GPSisr ); 180 | #endif 181 | } 182 | 183 | //-------------------------- 184 | 185 | void loop() 186 | { 187 | GPSloop(); 188 | } 189 | -------------------------------------------------------------------------------- /examples/NMEA/NMEA.ino: -------------------------------------------------------------------------------- 1 | #include 2 | 3 | //====================================================================== 4 | // Program: NMEA.ino 5 | // 6 | // Description: This program uses the fix-oriented methods available() and 7 | // read() to handle complete fix structures. 8 | // 9 | // When the last character of the LAST_SENTENCE_IN_INTERVAL (see NMEAGPS_cfg.h) 10 | // is decoded, a completed fix structure becomes available and is returned 11 | // from read(). The new fix is saved the 'fix' structure, and can be used 12 | // anywhere, at any time. 13 | // 14 | // If no messages are enabled in NMEAGPS_cfg.h, or 15 | // no 'gps_fix' members are enabled in GPSfix_cfg.h, no information will be 16 | // parsed, copied or printed. 17 | // 18 | // Prerequisites: 19 | // 1) Your GPS device has been correctly powered. 20 | // Be careful when connecting 3.3V devices. 21 | // 2) Your GPS device is correctly connected to an Arduino serial port. 22 | // See GPSport.h for the default connections. 23 | // 3) You know the default baud rate of your GPS device. 24 | // If 9600 does not work, use NMEAdiagnostic.ino to 25 | // scan for the correct baud rate. 26 | // 4) LAST_SENTENCE_IN_INTERVAL is defined to be the sentence that is 27 | // sent *last* in each update interval (usually once per second). 28 | // The default is NMEAGPS::NMEA_RMC (see NMEAGPS_cfg.h). Other 29 | // programs may need to use the sentence identified by NMEAorder.ino. 30 | // 5) NMEAGPS_RECOGNIZE_ALL is defined in NMEAGPS_cfg.h 31 | // 32 | // 'Serial' is for debug output to the Serial Monitor window. 33 | // 34 | // License: 35 | // Copyright (C) 2014-2017, SlashDevin 36 | // 37 | // This file is part of NeoGPS 38 | // 39 | // NeoGPS is free software: you can redistribute it and/or modify 40 | // it under the terms of the GNU General Public License as published by 41 | // the Free Software Foundation, either version 3 of the License, or 42 | // (at your option) any later version. 43 | // 44 | // NeoGPS is distributed in the hope that it will be useful, 45 | // but WITHOUT ANY WARRANTY; without even the implied warranty of 46 | // MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the 47 | // GNU General Public License for more details. 48 | // 49 | // You should have received a copy of the GNU General Public License 50 | // along with NeoGPS. If not, see . 51 | // 52 | //====================================================================== 53 | 54 | //------------------------------------------------------------------------- 55 | // The GPSport.h include file tries to choose a default serial port 56 | // for the GPS device. If you know which serial port you want to use, 57 | // edit the GPSport.h file. 58 | 59 | #include 60 | 61 | //------------------------------------------------------------ 62 | // For the NeoGPS example programs, "Streamers" is common set 63 | // of printing and formatting routines for GPS data, in a 64 | // Comma-Separated Values text format (aka CSV). The CSV 65 | // data will be printed to the "debug output device". 66 | // If you don't need these formatters, simply delete this section. 67 | 68 | #include 69 | 70 | //------------------------------------------------------------ 71 | // This object parses received characters 72 | // into the gps.fix() data structure 73 | 74 | static NMEAGPS gps; 75 | 76 | //------------------------------------------------------------ 77 | // Define a set of GPS fix information. It will 78 | // hold on to the various pieces as they are received from 79 | // an RMC sentence. It can be used anywhere in your sketch. 80 | 81 | static gps_fix fix; 82 | 83 | //---------------------------------------------------------------- 84 | // This function gets called about once per second, during the GPS 85 | // quiet time. It's the best place to do anything that might take 86 | // a while: print a bunch of things, write to SD, send an SMS, etc. 87 | // 88 | // By doing the "hard" work during the quiet time, the CPU can get back to 89 | // reading the GPS chars as they come in, so that no chars are lost. 90 | 91 | static void doSomeWork() 92 | { 93 | // Print all the things! 94 | 95 | trace_all( DEBUG_PORT, gps, fix ); 96 | 97 | } // doSomeWork 98 | 99 | //------------------------------------ 100 | // This is the main GPS parsing loop. 101 | 102 | static void GPSloop() 103 | { 104 | while (gps.available( gpsPort )) { 105 | fix = gps.read(); 106 | doSomeWork(); 107 | } 108 | 109 | } // GPSloop 110 | 111 | //-------------------------- 112 | 113 | void setup() 114 | { 115 | DEBUG_PORT.begin(9600); 116 | while (!DEBUG_PORT) 117 | ; 118 | 119 | DEBUG_PORT.print( F("NMEA.INO: started\n") ); 120 | DEBUG_PORT.print( F(" fix object size = ") ); 121 | DEBUG_PORT.println( sizeof(gps.fix()) ); 122 | DEBUG_PORT.print( F(" gps object size = ") ); 123 | DEBUG_PORT.println( sizeof(gps) ); 124 | DEBUG_PORT.println( F("Looking for GPS device on " GPS_PORT_NAME) ); 125 | 126 | #ifndef NMEAGPS_RECOGNIZE_ALL 127 | #error You must define NMEAGPS_RECOGNIZE_ALL in NMEAGPS_cfg.h! 128 | #endif 129 | 130 | #ifdef NMEAGPS_INTERRUPT_PROCESSING 131 | #error You must *NOT* define NMEAGPS_INTERRUPT_PROCESSING in NMEAGPS_cfg.h! 132 | #endif 133 | 134 | #if !defined( NMEAGPS_PARSE_GGA ) & !defined( NMEAGPS_PARSE_GLL ) & \ 135 | !defined( NMEAGPS_PARSE_GSA ) & !defined( NMEAGPS_PARSE_GSV ) & \ 136 | !defined( NMEAGPS_PARSE_RMC ) & !defined( NMEAGPS_PARSE_VTG ) & \ 137 | !defined( NMEAGPS_PARSE_ZDA ) & !defined( NMEAGPS_PARSE_GST ) 138 | 139 | DEBUG_PORT.println( F("\nWARNING: No NMEA sentences are enabled: no fix data will be displayed.") ); 140 | 141 | #else 142 | if (gps.merging == NMEAGPS::NO_MERGING) { 143 | DEBUG_PORT.print ( F("\nWARNING: displaying data from ") ); 144 | DEBUG_PORT.print ( gps.string_for( LAST_SENTENCE_IN_INTERVAL ) ); 145 | DEBUG_PORT.print ( F(" sentences ONLY, and only if ") ); 146 | DEBUG_PORT.print ( gps.string_for( LAST_SENTENCE_IN_INTERVAL ) ); 147 | DEBUG_PORT.println( F(" is enabled.\n" 148 | " Other sentences may be parsed, but their data will not be displayed.") ); 149 | } 150 | #endif 151 | 152 | DEBUG_PORT.print ( F("\nGPS quiet time is assumed to begin after a ") ); 153 | DEBUG_PORT.print ( gps.string_for( LAST_SENTENCE_IN_INTERVAL ) ); 154 | DEBUG_PORT.println( F(" sentence is received.\n" 155 | " You should confirm this with NMEAorder.ino\n") ); 156 | 157 | trace_header( DEBUG_PORT ); 158 | DEBUG_PORT.flush(); 159 | 160 | gpsPort.begin( 9600 ); 161 | } 162 | 163 | //-------------------------- 164 | 165 | void loop() 166 | { 167 | GPSloop(); 168 | } 169 | -------------------------------------------------------------------------------- /src/ublox/ubxNMEA.cpp: -------------------------------------------------------------------------------- 1 | // Copyright (C) 2014-2017, SlashDevin 2 | // 3 | // This file is part of NeoGPS 4 | // 5 | // NeoGPS is free software: you can redistribute it and/or modify 6 | // it under the terms of the GNU General Public License as published by 7 | // the Free Software Foundation, either version 3 of the License, or 8 | // (at your option) any later version. 9 | // 10 | // NeoGPS is distributed in the hope that it will be useful, 11 | // but WITHOUT ANY WARRANTY; without even the implied warranty of 12 | // MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the 13 | // GNU General Public License for more details. 14 | // 15 | // You should have received a copy of the GNU General Public License 16 | // along with NeoGPS. If not, see . 17 | 18 | #include "ublox/ubxNMEA.h" 19 | 20 | // Disable the entire file if derived types are not allowed, 21 | // *or* if no PUBX messages are enabled. 22 | #if defined( NMEAGPS_DERIVED_TYPES) & \ 23 | (defined(NMEAGPS_PARSE_PUBX_00) | defined(NMEAGPS_PARSE_PUBX_04)) 24 | 25 | //--------------------------------------------- 26 | 27 | bool ubloxNMEA::parseField(char chr) 28 | { 29 | if (nmeaMessage >= (nmea_msg_t) PUBX_FIRST_MSG) { 30 | 31 | switch (nmeaMessage) { 32 | 33 | case PUBX_00: return parsePUBX_00( chr ); 34 | 35 | #if defined(NMEAGPS_PARSE_PUBX_04) | defined(NMEAGPS_RECOGNIZE_ALL) 36 | case PUBX_04: return parsePUBX_04( chr ); 37 | #endif 38 | 39 | default: 40 | break; 41 | } 42 | 43 | } else 44 | 45 | // Delegate 46 | return NMEAGPS::parseField(chr); 47 | 48 | 49 | return true; 50 | 51 | } // parseField 52 | 53 | //---------------------------- 54 | 55 | bool ubloxNMEA::parsePUBX_00( char chr ) 56 | { 57 | bool ok = true; 58 | 59 | switch (fieldIndex) { 60 | case 1: 61 | // The first field is actually a message subtype 62 | if (chrCount == 0) 63 | ok = (chr == '0'); 64 | 65 | else if (chrCount == 1) { 66 | switch (chr) { 67 | #if defined(NMEAGPS_PARSE_PUBX_00) | defined(NMEAGPS_RECOGNIZE_ALL) 68 | case '0': break; 69 | #endif 70 | #if defined(NMEAGPS_PARSE_PUBX_04) | defined(NMEAGPS_RECOGNIZE_ALL) 71 | case '4': nmeaMessage = (nmea_msg_t) PUBX_04; break; 72 | #endif 73 | default : ok = false; 74 | } 75 | 76 | } else // chrCount > 1 77 | ok = (chr == ','); 78 | break; 79 | 80 | #ifdef NMEAGPS_PARSE_PUBX_00 81 | case 2: return parseTime( chr ); 82 | PARSE_LOC(3); 83 | case 7: return parseAlt( chr ); 84 | case 8: return parseFix( chr ); 85 | case 9: // use Horizontal accuracy for both lat and lon errors 86 | #if defined(GPS_FIX_LAT_ERR) 87 | ok = parse_lat_err( chr ); 88 | #if defined(GPS_FIX_LON_ERR) 89 | // When the lat_err field is finished, 90 | // copy it to the lon_err field. 91 | if (chr == ',') { 92 | m_fix.valid.lon_err = m_fix.valid.lat_err; 93 | if (m_fix.valid.lon_err) 94 | m_fix.lon_err_cm = m_fix.lat_err_cm; 95 | } 96 | #endif 97 | 98 | #elif defined(GPS_FIX_LON_ERR) 99 | ok = parse_lon_err( chr ); 100 | #endif 101 | break; 102 | case 10: return parse_alt_err( chr ); // vertical accuracy 103 | case 11: 104 | #ifdef GPS_FIX_SPEED 105 | ok = parseSpeed( chr ); // PUBX,00 provides speed in km/h! 106 | 107 | if ((chr == ',') && m_fix.valid.speed) { 108 | uint32_t kph = m_fix.spd.int32_000(); 109 | uint32_t nmiph = (kph * 1000) / gps_fix::M_PER_NMI; 110 | m_fix.spd.whole = nmiph / 1000; 111 | m_fix.spd.frac = (nmiph - m_fix.spd.whole*1000); 112 | // Convert to Nautical Miles/Hour 113 | } 114 | #endif 115 | break; 116 | case 12: return parseHeading( chr ); 117 | case 13: return parseVelocityDown( chr ); 118 | case 15: return parseHDOP( chr ); 119 | case 16: return parseVDOP( chr ); 120 | case 18: return parseSatellites( chr ); 121 | #endif 122 | } 123 | 124 | return ok; 125 | 126 | } // parsePUBX_00 127 | 128 | //--------------------------------------------- 129 | 130 | bool ubloxNMEA::parsePUBX_04( char chr ) 131 | { 132 | #ifdef NMEAGPS_PARSE_PUBX_04 133 | switch (fieldIndex) { 134 | case 2: return parseTime( chr ); 135 | case 3: return parseDDMMYY( chr ); 136 | } 137 | #endif 138 | 139 | return true; 140 | 141 | } // parsePUBX_04 142 | 143 | //--------------------------------------------- 144 | 145 | bool ubloxNMEA::parseFix( char chr ) 146 | { 147 | if (chrCount == 0) { 148 | NMEAGPS_INVALIDATE( status ); 149 | if (chr == 'N') 150 | m_fix.status = gps_fix::STATUS_NONE; 151 | else if (chr == 'T') 152 | m_fix.status = gps_fix::STATUS_TIME_ONLY; 153 | else if (chr == 'R') 154 | m_fix.status = gps_fix::STATUS_EST; 155 | else if (chr == 'G') 156 | m_fix.status = gps_fix::STATUS_STD; 157 | else if (chr == 'D') 158 | m_fix.status = gps_fix::STATUS_DGPS; 159 | 160 | } else if (chrCount == 1) { 161 | 162 | if (((chr == 'T') && (m_fix.status == gps_fix::STATUS_TIME_ONLY)) || 163 | ((chr == 'K') && (m_fix.status == gps_fix::STATUS_EST)) || 164 | (((chr == '2') || (chr == '3')) && 165 | ((m_fix.status == gps_fix::STATUS_STD) || 166 | (m_fix.status == gps_fix::STATUS_DGPS))) || 167 | ((chr == 'F') && (m_fix.status == gps_fix::STATUS_NONE))) 168 | // status based on first char was ok guess 169 | m_fix.valid.status = true; 170 | 171 | else if ((chr == 'R') && (m_fix.status == gps_fix::STATUS_DGPS)) { 172 | m_fix.status = gps_fix::STATUS_EST; // oops, was DR instead 173 | m_fix.valid.status = true; 174 | } 175 | } 176 | 177 | return true; 178 | } 179 | 180 | //--------------------------------------------- 181 | 182 | bool ubloxNMEA::parseVelocityDown( char chr ) 183 | { 184 | #ifdef GPS_FIX_VELNED 185 | if (chrCount == 0) 186 | NMEAGPS_INVALIDATE( velned ); 187 | 188 | // Checks for alias size. 189 | char test[ (int)sizeof(m_fix.velocity_down) - (int)sizeof(gps_fix::whole_frac) ]; 190 | 191 | gps_fix::whole_frac *temp = (gps_fix::whole_frac *) &m_fix.velocity_down; // an alias for parsing 192 | 193 | if (parseFloat( *temp, chr, 3 )) { // 0.001 m/s 194 | 195 | if (chr == ',') { 196 | // convert the temporary whole_frac values in place 197 | m_fix.valid.velned = (chrCount > 0); 198 | if (m_fix.valid.velned) { 199 | m_fix.velocity_down = (temp->int32_000() + 5) / 10L; // mm/s to cm/s 200 | } 201 | } 202 | } 203 | #endif 204 | 205 | return true; 206 | 207 | } // parseVelocityDown 208 | 209 | #endif // DERIVED types and at least one PUBX message enabled 210 | -------------------------------------------------------------------------------- /examples/Tabular/Tabular.ino: -------------------------------------------------------------------------------- 1 | #include 2 | 3 | NMEAGPS gps; 4 | 5 | //====================================================================== 6 | // Program: SyncTime.ino 7 | // 8 | // Description: This program displays all GPS fields in the default configuration 9 | // in a tabular display. To be comparable to other libraries' tabular displays, 10 | // you must also enable HDOP in GPSfix_cfg.h. 11 | // 12 | // Most NeoGPS examples display *all* configured GPS fields in a CSV format 13 | // (e.g., NMEA.ino). 14 | // 15 | // Prerequisites: 16 | // 1) NMEA.ino works with your device (correct TX/RX pins and baud rate) 17 | // 2) GPS_FIX_HDOP is defined in GPSfix_cfg.h 18 | // 19 | // 'Serial' is for debug output to the Serial Monitor window. 20 | // 21 | // License: 22 | // Copyright (C) 2014-2017, SlashDevin 23 | // 24 | // This file is part of NeoGPS 25 | // 26 | // NeoGPS is free software: you can redistribute it and/or modify 27 | // it under the terms of the GNU General Public License as published by 28 | // the Free Software Foundation, either version 3 of the License, or 29 | // (at your option) any later version. 30 | // 31 | // NeoGPS is distributed in the hope that it will be useful, 32 | // but WITHOUT ANY WARRANTY; without even the implied warranty of 33 | // MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the 34 | // GNU General Public License for more details. 35 | // 36 | // You should have received a copy of the GNU General Public License 37 | // along with NeoGPS. If not, see . 38 | // 39 | //====================================================================== 40 | 41 | #include 42 | 43 | //----------------- 44 | // Check configuration 45 | 46 | #ifndef GPS_FIX_HDOP 47 | #error You must uncomment GPS_FIX_HDOP in GPSfix_cfg.h! 48 | #endif 49 | 50 | //----------------- 51 | 52 | static const NeoGPS::Location_t London( 51.508131, -0.128002 ); 53 | 54 | void setup() 55 | { 56 | DEBUG_PORT.begin(9600); 57 | 58 | DEBUG_PORT.println 59 | ( 60 | F( "Testing NeoGPS library\n\n" 61 | "Sats HDOP Latitude Longitude Date Time Alt Speed Heading -- To London -- Chars Sentences Errors\n" 62 | " (deg) (deg) (m) Dist Dir\n" ) 63 | ); 64 | 65 | repeat( '-', 133 ); 66 | 67 | gpsPort.begin(9600); 68 | } 69 | 70 | //----------------- 71 | 72 | void loop() 73 | { 74 | if (gps.available( gpsPort )) { 75 | gps_fix fix = gps.read(); 76 | 77 | float bearingToLondon = fix.location.BearingToDegrees( London ); 78 | bool validDT = fix.valid.date & fix.valid.time; 79 | 80 | print( fix.satellites , fix.valid.satellites, 3 ); 81 | print( fix.hdop/1000.0 , fix.valid.hdop , 6, 2 ); 82 | print( fix.latitude () , fix.valid.location , 10, 6 ); 83 | print( fix.longitude() , fix.valid.location , 11, 6 ); 84 | print( fix.dateTime , validDT , 20 ); 85 | print( fix.altitude () , fix.valid.altitude , 7, 2 ); 86 | print( fix.speed_kph() , fix.valid.speed , 7, 2 ); 87 | print( fix.heading () , fix.valid.heading , 7, 2 ); 88 | print( compassDir( fix.heading () ) , fix.valid.heading , 4 ); 89 | print( fix.location.DistanceKm( London ), fix.valid.location , 5 ); 90 | print( bearingToLondon , fix.valid.location , 7, 2 ); 91 | print( compassDir( bearingToLondon ) , fix.valid.location , 4 ); 92 | 93 | print( gps.statistics.chars , true, 10 ); 94 | print( gps.statistics.ok , true, 6 ); 95 | print( gps.statistics.errors, true, 6 ); 96 | 97 | DEBUG_PORT.println(); 98 | } 99 | } 100 | 101 | //----------------- 102 | // Print utilities 103 | 104 | static void repeat( char c, int8_t len ) 105 | { 106 | for (int8_t i=0; i= directions) 194 | dir -= directions; 195 | 196 | return (const __FlashStringHelper *) pgm_read_ptr( &dirStrings[ dir ] ); 197 | 198 | } // compassDir 199 | -------------------------------------------------------------------------------- /examples/NMEArevGeoCache/NMEArevGeoCache.ino: -------------------------------------------------------------------------------- 1 | #include 2 | 3 | //====================================================================== 4 | // Program: NMEArevGeoCache.ino 5 | // 6 | // Description: Activates a servo when the current location is 7 | // close enough to the target location. 8 | // 9 | // Prerequisites: 10 | // 1) NMEA.ino works with your device (correct TX/RX pins and baud rate) 11 | // 2) The RMC sentence has been enabled. 12 | // 3) Your device sends an RMC sentence (e.g., $GPRMC). 13 | // 14 | // Additional Hardware examples: 15 | // 16x2 Character LCD: https://www.adafruit.com/products/181) 16 | // Servo : TPro Micro SG90 https://www.adafruit.com/products/169 17 | // 18 | // 'Serial' is for debug output to the Serial Monitor window. 19 | // 20 | // Credits: 21 | // This is simplified version of bnordlund9's Geobox: 22 | // http://www.youtube.com/watch?v=g0060tcuofg 23 | // 24 | // Engagement Box by Kenton Harris 11/12/2012 25 | // 26 | // Reverse Geocache idea by Mikal Hart of http://arduiniana.org/ 27 | // 28 | // License: 29 | // Copyright (C) 2014-2017, SlashDevin 30 | // 31 | // This file is part of NeoGPS 32 | // 33 | // NeoGPS is free software: you can redistribute it and/or modify 34 | // it under the terms of the GNU General Public License as published by 35 | // the Free Software Foundation, either version 3 of the License, or 36 | // (at your option) any later version. 37 | // 38 | // NeoGPS is distributed in the hope that it will be useful, 39 | // but WITHOUT ANY WARRANTY; without even the implied warranty of 40 | // MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the 41 | // GNU General Public License for more details. 42 | // 43 | // You should have received a copy of the GNU General Public License 44 | // along with NeoGPS. If not, see . 45 | // 46 | //====================================================================== 47 | 48 | #include 49 | 50 | //------------------------------------------------------------ 51 | // Check that the config files are set up properly 52 | 53 | #if !defined( NMEAGPS_PARSE_RMC ) & \ 54 | !defined( NMEAGPS_PARSE_GGA ) & \ 55 | !defined( NMEAGPS_PARSE_GLL ) 56 | #error You must uncomment at least one of NMEAGPS_PARSE_RMC, NMEAGPS_PARSE_GGA or NMEAGPS_PARSE_GLL in NMEAGPS_cfg.h! 57 | #endif 58 | 59 | #if !defined( GPS_FIX_LOCATION ) 60 | #error You must uncomment GPS_FIX_LOCATION in GPSfix_cfg.h! 61 | #endif 62 | 63 | //------------------------------------------------------------ 64 | // Additional Hardware includes 65 | #include 66 | //#include 67 | 68 | #include 69 | PWMServo servoLatch; 70 | const int servoLock = 180; // angle (deg) of "locked" servo 71 | const int servoUnlock = 105; // angle (deg) of "unlocked" servo 72 | 73 | using namespace NeoGPS; 74 | NMEAGPS gps; 75 | 76 | float range; // current distance from HERE to THERE 77 | const float CLOSE_ENOUGH = 300.0; // miles, change for your needs 78 | 79 | LiquidCrystal lcd(7, 8, 6, 10, 11, 12); 80 | 81 | const int fixLEDPin = 4; 82 | const int servoPin = 9; 83 | 84 | // The target location, in degrees * 10,000,000 85 | Location_t there( 384602500, -1098191667L ); 86 | // 38°27'36.2"N 109°49'15.4"W 87 | 88 | void setup() 89 | { 90 | servoLatch.attach(SERVO_PIN_A); 91 | servoLatch.write(servoLock); 92 | delay(50); 93 | 94 | lcd.begin(16, 2); 95 | 96 | Serial.begin(9600); 97 | Serial.println( F("Debug GPS Test:") ); 98 | 99 | gpsPort.begin(9600); 100 | 101 | // Configure GPS (these are Adafruit GPS commands - your brand may be different) 102 | gpsPort.print 103 | ( F( "$PMTK314,0,1,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0*29\r\n" // RMC only... 104 | "$PMTK220,1000*1F\r\n" ) ); // ...and 1 Hz update rate 105 | 106 | } // setup 107 | 108 | void loop() 109 | { 110 | static uint8_t warningState = 0; 111 | static uint32_t lastFixTime, lastDotTime; 112 | 113 | while (gps.available( gpsPort )) { 114 | gps_fix fix = gps.read(); // save the latest 115 | 116 | // Set the "fix" LED to on or off 117 | bool gpsWasFixed = fix.valid.status && (fix.status >= gps_fix::STATUS_STD); 118 | digitalWrite( fixLEDPin, gpsWasFixed ); 119 | 120 | // When we have a location, calculate how far away we are from "there". 121 | if (fix.valid.location) { 122 | lastFixTime = millis(); 123 | 124 | range = fix.location.DistanceMiles( there ); 125 | 126 | //for GPS debug 127 | DEBUG_PORT.print( F("Here: ") ); 128 | //printDMS( DEBUG_PORT, fix.location ); 129 | printAsFloat( DEBUG_PORT, fix.location ); 130 | 131 | DEBUG_PORT.print( F(" There: ") ); 132 | //printDMS( DEBUG_PORT, there ); 133 | printAsFloat( DEBUG_PORT, there ); 134 | 135 | DEBUG_PORT.print( F("Range: ") ); 136 | DEBUG_PORT.print( range ); 137 | DEBUG_PORT.println( F(" Miles") ); 138 | 139 | // Are we there? 140 | if (range < CLOSE_ENOUGH) { 141 | lcd.setCursor(0,1); 142 | lcd.println( F("Box Unlocking...") ); 143 | delay(500); 144 | servoLatch.write(servoUnlock); 145 | 146 | lcd.clear(); 147 | lcd.setCursor(0,1); 148 | lcd.print( F("Happy Birthday") ); 149 | 150 | for (;;); // hang here 151 | } 152 | 153 | // Nope, just give a little feedback... 154 | lcd.clear(); 155 | lcd.setCursor(0,0); 156 | lcd.print( F("Signal Locked") ); 157 | lcd.setCursor(0,1); 158 | lcd.print( range ); 159 | lcd.print( F(" Miles") ); 160 | 161 | warningState = 0; // restart in case we lose the fix later 162 | } 163 | } 164 | 165 | // Display warnings when the GPS hasn't had a fix for a while 166 | 167 | if (millis() - lastFixTime > 2000UL) { 168 | 169 | if (warningState == 0) { 170 | 171 | // First, show the warning message... 172 | lcd.clear(); 173 | lcd.setCursor(0,0); 174 | lcd.print( F("Acquiring Signal") ); 175 | 176 | warningState = 1; 177 | 178 | } else if (warningState < 10) { 179 | 180 | // ...then some dots, two per second... 181 | if (millis() - lastDotTime > 500UL ) { 182 | lastDotTime = millis(); 183 | lcd.setCursor( warningState-1, 1 ); 184 | lcd.print( '.' ); 185 | 186 | warningState++; 187 | } 188 | 189 | } else if (warningState == 10) { 190 | // ... then tell them what to do. 191 | lcd.setCursor(0,1); 192 | lcd.println( F("Take box outside") ); 193 | 194 | // Don't display anything else until location is valid 195 | warningState++; // 11 196 | } 197 | } 198 | } // loop 199 | 200 | //---------------------------------------------------------------- 201 | 202 | #include "DMS.h" 203 | 204 | void printDMS( Print & outs, const Location_t & loc ) 205 | { 206 | DMS_t dms; 207 | dms.From( loc.lat() ); 208 | 209 | outs.print( dms.NS() ); 210 | outs << dms; 211 | 212 | dms.From( loc.lon() ); 213 | outs.print( dms.EW() ); 214 | outs << dms; 215 | 216 | } // printDMS 217 | 218 | //---------------------------------------------------------------- 219 | 220 | void printL( Print & outs, int32_t degE7 ) 221 | { 222 | // Extract and print negative sign 223 | if (degE7 < 0) { 224 | degE7 = -degE7; 225 | outs.print( '-' ); 226 | } 227 | 228 | // Whole degrees 229 | int32_t deg = degE7 / 10000000L; 230 | outs.print( deg ); 231 | outs.print( '.' ); 232 | 233 | // Get fractional degrees 234 | degE7 -= deg*10000000L; 235 | 236 | // Print leading zeroes, if needed 237 | int32_t factor = 1000000L; 238 | while ((degE7 < factor) && (factor > 1L)){ 239 | outs.print( '0' ); 240 | factor /= 10L; 241 | } 242 | 243 | // Print fractional degrees 244 | outs.print( degE7 ); 245 | 246 | } // printL 247 | 248 | //---------------------------------------------------------------- 249 | 250 | void printAsFloat( Print & outs, const Location_t &loc ) 251 | { 252 | printL( outs, loc.lat() ); // display decimal degrees or... 253 | // printDMS( outs, loc.lat() ); // ... display degrees minutes seconds 254 | 255 | outs.print( F(", ") ); 256 | 257 | printL( outs, loc.lat() ); 258 | // printDMS( outs, loc.lat() ); 259 | } 260 | -------------------------------------------------------------------------------- /extras/doc/Choosing.md: -------------------------------------------------------------------------------- 1 | # Choosing your configuration 2 | There are only a few configurations provided by examples. If your application needs something slightly different, here is a general configuration process. 3 | 4 | ## What number do you want? 5 | First, decide which data members of `gps_fix` and `NMEAGPS` you need (see [Data Model](Data Model.md) for member descriptions). Those members **must** be enabled in `GPSfix_cfg.h`. 6 | 7 | Next, figure out what messages can fill out those members, because those messages **must** be enabled in `NMEAGPS_cfg.h`. Here is a table of the NMEA messages parsed by NeoGPS, and which data members they affect: 8 | 9 | 10 | 11 | 12 | 13 | 14 | 15 | 16 | 17 | 18 | 19 | 20 | 21 | 22 | 23 | 24 | 25 | 26 | 27 | 28 | 29 | 30 | 31 | 32 | 33 | 34 | 35 | 36 | 37 | 38 | 39 | 40 | 41 | 42 | 43 | 44 | 45 | 46 | 47 | 48 | 49 | 50 | 51 | 52 | 53 | 54 | 55 | 56 | 57 | 58 | 59 | 60 | 61 | 62 | 63 | 64 | 65 | 66 | 67 | 68 | 69 | 70 | 71 | 72 | 73 | 74 | 75 | 76 | 77 | 78 | 79 | 80 | 81 | 82 | 83 | 84 | 85 | 86 | 87 | 88 | 89 | 90 | 91 | 92 | 93 | 94 | 95 | 96 | 97 | 98 | 99 | 100 | 101 | 102 | 103 | 104 | 105 | 106 | 107 | 108 | 109 | 110 | 111 | 112 | 113 | 114 | 115 | 116 | 117 | 118 | 119 | 120 | 121 | 122 | 123 | 124 | 125 | 126 | 127 | 128 | 129 | 130 | 131 | 132 | 133 | 134 | 135 | 136 | 137 | 138 | 139 | 140 | 141 | 142 | 143 | 144 | 145 | 146 | 147 | 148 | 149 | 150 | 151 | 152 | 153 | 154 | 155 | 156 | 157 | 158 | 159 | 160 | 161 | 162 | 163 | 164 | 165 | 166 | 167 | 168 | 169 | 170 | 171 | 172 | 173 | 174 | 175 | 176 | 177 | 178 | 179 | 180 | 181 | 184 | 185 | 186 | 187 | 188 | 189 | 190 | 191 | 192 | 193 | 194 | 195 | 196 | 197 | 198 | 199 | 200 | 201 | 202 | 203 | 204 | 205 | 206 | 207 | 208 | 209 | 212 | 213 | 214 | 215 | 216 | 217 | 218 | 219 | 220 | 221 | 222 | 223 | 224 | 225 | 226 | 227 | 228 | 229 | 230 | 231 | 232 | 233 | 234 | 235 | 236 | 237 | 238 | 239 | 240 | 241 | 242 | 243 | 244 | 245 | 246 | 247 | 248 | 249 | 250 |

Message

Data Member

GGA


GLL


GSA


GST


GSV


RMC


VTG


ZDA


PUBX
001


PUBX
041


class gps_fix

status

*** ** *

date2

* * *

time2

** * * ***

lat/lon

** * *

altitude

* *

speed

** *

heading

** *

satellites 3

* * *

HDOP

* * *

VDOP

* *

PDOP

*

TDOP

*

Velocity North,
182 | East,
183 | Down

* 4
* 4
*

lat, lon, alt error

* *

speed error,
210 | heading error,
211 | time error 5

class NMEAGPS

satellite IDs 3

* *

satellite azimuth,
  elevation and
  signal strength 3

*
251 | 252 | This table illustrates the poor design of the NMEA message set: it requires multiple messages to deliver a complete fix (i.e., all members of `gps_fix`). This also explains why many manufacturers provide proprietary messages that *are* more complete. Above, you can see that the `$PUBX,00`1 message contains all members except `date`. 253 | 254 | While the manufacturer's specification will document all sentences supported for your device, you can also find general descriptions of many NMEA sentences [here](http://www.gpsinformation.org/dale/nmea.htm), [here](http://aprs.gids.nl/nmea/) or [here](http://www.catb.org/gpsd/NMEA.txt). 255 | 256 |
257 | 258 | 259 | 1 The NMEA proprietary messages "PUBX" are only availble in the `ubloxNMEA` class. See [ublox-specific instructions](ublox.md) for adding this class to your configuration. 260 | 261 | 2 Date and time are both stored in one member of `gps_fix`, called `dateTime`. The `fix.dateTime` member is a C++ class that has both date-oriented members (Date, Month and Year) and time-oriented members (Hours, Minutes and Seconds). See [NeoTime.h](/src/NeoTime.h) for the complete description and capabilities of the `dateTime` member, such as date/time arithmetic and conversion to/from seconds since the epoch. Hundredths of a second are stored in a separate member of `gps_fix`, called `dateTime_cs`, and can also be accessed with the functions `dateTime_ms()` and `dateTime_us()`. 262 | 263 | 3 The `fix.satellites` member identifies how many of these satellites were used to calculate a fix. The number of satellites' information available in the `gps.satellites[]` array is stored in `gps.sat_count`. This the total number of satellites that may or may not be used for calculating a fix. 264 | 265 | 4 Only Velocity Down is provided by the PUBX,00 message. A utility routine is provided to *calculate* Velocity North and East from Speed and Heading, if enabled. See `calculateNorthAndEastVelocityFromSpeedAndHeading` in gps_fix.h. 266 | 267 | 5 These fields are only available from UBX binary messages. 268 | -------------------------------------------------------------------------------- /extras/doc/Examples.md: -------------------------------------------------------------------------------- 1 | Examples 2 | ====== 3 | In an attempt to be reusable in a variety of different programming styles, this library supports: 4 | * sync or async operation (main `loop()` vs interrupt processing) 5 | * fused or not fused (multiple reports into one fix) 6 | * optional buffering of fixes 7 | * optional floating point 8 | * configurable message sets, including hooks for implementing proprietary NMEA messages 9 | * configurable message fields 10 | * multiple protocols from same device 11 | 12 | These example programs demonstrate how to use the classes in the different programming styles: 13 | * [NMEA](/examples/NMEA/NMEA.ino) - sync, single fix, standard NMEA only (RMC sentence only) 14 | * [NMEA_isr](/examples/NMEA_isr/NMEA_isr.ino) - **async**, single fix, standard NMEA only (RMC sentence only) 15 | * [NMEAblink](/examples/NMEAblink/NMEAblink.ino) - sync, single fix, standard NMEA only, minimal example, only blinks LED 16 | * [NMEAloc](/examples/NMEAloc/NMEAloc.ino) - sync, single fix, minimal example using only standard NMEA RMC sentence 17 | * [NMEAlocDMS](/examples/NMEAlocDMS/NMEAlocDMS.ino) - same as NMEAloc.ino, but displays location in Degrees, Minutes and Seconds 18 | * [NMEAaverage](/examples/NMEAaverage/NMEAaverage.ino) - sync, single fix, averages a high-accuracy location over time 19 | * [NMEAtimezone](/examples/NMEAtimezone/NMEAtimezone.ino) - same as NMEAloc.ino, but displays local time instead of UTC (GMT) 20 | * [NMEASDlog](/examples/NMEASDlog/NMEASDlog.ino) - **async**, buffered fixes, standard NMEA only (RMC sentence only), logging to SD card 21 | * [PUBX](/examples/PUBX/PUBX.ino) - sync, coherent fix, standard NMEA + ublox proprietary NMEA 22 | * [ublox](/examples/ublox/ublox.ino) - sync or **async**, coherent fix, ublox binary protocol UBX 23 | 24 | Preprocessor symbol `USE_FLOAT` can be used in [Streamers.cpp](/src/Streamers.cpp) to select integer or floating-point output. 25 | 26 | See also important information in `NMEAorder.ino` below, and the [Installing](Installing.md), [Configurations](Configurations.md) and [Troubleshooting](Troubleshooting.md) sections. 27 | 28 | ##Diagnostics 29 | Several programs are provided to help diagnose GPS device problems: 30 | 31 | ### Connection and Baud Rate 32 | 33 | * [NMEAdiagnostic](/examples/NMEAdiagnostic/NMEAdiagnostic.ino) 34 | 35 | This program listens for sentences and, if none are detected, tries a different baud rate. When sentences are detected, the correct baud rate is displayed. The received data may help you determine the problem (e.g., dropped characters or binary protocol). 36 | 37 | See the [Troubleshooting](Troubleshooting.md) section for more details. 38 | 39 | ### Sentence order 40 | 41 | * [NMEAorder](/examples/NMEAorder/NMEAorder.ino) 42 | 43 | This program determines the order of NMEA sentences sent during each 1-second interval: 44 | 45 | ``` 46 | NMEAorder.INO: started 47 | fix object size = 44 48 | NMEAGPS object size = 72 49 | Looking for GPS device on Serial1 50 | ..................... 51 | Sentence order in each 1-second interval: 52 | RMC 53 | VTG 54 | GGA 55 | GSA 56 | GSV 57 | GSV 58 | GSV 59 | GSV 60 | GLL 61 | ``` 62 | 63 | The last sentence is of particular interest, as it is used to determine when the quiet time begins. All example programs **depend** on knowing the last sentence (see [Quiet Time Interval](Troubleshooting#quiet-time-interval)). 64 | 65 | ### Self-test Program 66 | 67 | * [NMEAtest](/examples/NMEAtest/NMEAtest.ino) 68 | 69 | For this program, **No GPS device is required**. Test bytes are streamed from PROGMEM character arrays. Various strings are passed to `decode` and the expected pass or fail results are displayed. If **NeoGPS** is correctly configured, you should see this on your SerialMonitor: 70 | 71 | ``` 72 | NMEA test: started 73 | fix object size = 44 74 | NMEAGPS object size = 72 75 | Test string length = 75 76 | PASSED 11 tests. 77 | ------ Samples ------ 78 | Results format: 79 | Status,UTC Date/Time,Lat,Lon,Hdg,Spd,Alt,HDOP,VDOP,PDOP,Lat err,Lon err,Alt err,Sats,[sat], 80 | 81 | Input: $GPGGA,092725.00,4717.11399,N,00833.91590,E,1,8,1.01,499.6,M,48.0,M,,0*5B 82 | Results: 3,2000-01-01 09:27:25.00,472852332,85652650,,,49960,1010,,,,,,8,[], 83 | 84 | Input: $GPRMC,092725.00,A,2520.69213,S,13101.94948,E,0.004,77.52,091202,,,A*43 85 | Results: 3,2002-12-09 09:27:25.00,-253448688,1310324913,7752,4,,,,,,,,,[], 86 | 87 | Input: $GPRMC,162254.00,A,3647.6643,N,8957.5193,W,0.820,188.36,110706,,,A*49 88 | Results: 3,2006-07-11 16:22:54.00,367944050,-899586550,18836,820,,,,,,,,,[], 89 | 90 | Input: $GPRMC,235959.99,A,2149.65726,N,16014.69256,W,8.690,359.99,051015,9.47,E,A*26 91 | Results: 3,2015-10-05 23:59:59.99,218276210,-1602448760,35999,8690,,,,,,,,,[], 92 | 93 | Input: $GNGLL,0105.60764,S,03701.70233,E,225627.00,A,A*6B 94 | Results: 3,2000-01-01 22:56:27.00,-10934607,370283722,,,,,,,,,,,[], 95 | 96 | Input: $GPGGA,064951.000,2307.1256,N,12016.4438,E,1,8,0.95,39.9,M,17.8,M,,*63 97 | Results: 3,2000-01-01 06:49:51.00,231187600,1202740633,,,3990,950,,,,,,8,[], 98 | 99 | Input: $GPRMC,064951.000,A,2307.1256,N,12016.4438,E,0.03,165.48,260406,3.05,W,A*2C 100 | Results: 3,2006-04-26 06:49:51.00,231187600,1202740633,16548,30,,,,,,,,,[], 101 | 102 | Input: $GPVTG,165.48,T,,M,0.03,N,0.06,K,A*36 103 | Results: 3,,,,16548,30,,,,,,,,,[], 104 | 105 | Input: $GPGSA,A,3,29,21,26,15,18,09,06,10,,,,,2.32,0.95,2.11*00 106 | Results: 3,,,,,,,950,,2320,,,,,[], 107 | 108 | Input: $GPGSV,3,1,09,29,36,029,42,21,46,314,43,26,44,020,43,15,21,321,39*7D 109 | Results: ,,,,,,,,,,,,,9,[29,21,26,15,], 110 | 111 | Input: $GPGSV,3,2,09,18,26,314,40,09,57,170,44,06,20,229,37,10,26,084,37*77 112 | Results: ,,,,,,,,,,,,,9,[29,21,26,15,18,9,6,10,], 113 | 114 | Input: $GPGSV,3,3,09,07,,,26*73 115 | Results: ,,,,,,,,,,,,,9,[29,21,26,15,18,9,6,10,7,], 116 | 117 | Input: $GNGST,082356.00,1.8,,,,1.7,1.3,2.2*60 118 | Results: ,2000-01-01 08:23:56.00,,,,,,,,,170,130,,,[29,21,26,15,18,9,6,10,7,], 119 | 120 | Input: $GNRMC,083559.00,A,4717.11437,N,00833.91522,E,0.004,77.52,091202,,,A,V*33 121 | Results: 3,2002-12-09 08:35:59.00,472852395,85652537,7752,4,,,,,,,,,[29,21,26,15,18,9,6,10,7,], 122 | 123 | Input: $GNGGA,092725.00,4717.11399,N,00833.91590,E,1,08,1.01,499.6,M,48.0,M,,*45 124 | Results: 3,2000-01-01 09:27:25.00,472852332,85652650,,,49960,1010,,,,,,8,[29,21,26,15,18,9,6,10,7,], 125 | 126 | Input: $GLZDA,225627.00,21,09,2015,00,00*70 127 | Results: ,2015-09-21 22:56:27.00,,,,,,,,,,,,,[29,21,26,15,18,9,6,10,7,], 128 | 129 | --- floating point conversion tests --- 130 | 131 | Input: $GPGGA,092725.00,3242.9000,N,11705.8169,W,1,8,1.01,499.6,M,48.0,M,,0*49 132 | Results: 3,2000-01-01 09:27:25.00,327150000,-1170969483,,,49960,1010,,,,,,8,[29,21,26,15,18,9,6,10,7,], 133 | 134 | Input: $GPGGA,092725.00,3242.9000,N,11705.8170,W,1,8,1.01,499.6,M,48.0,M,,0*41 135 | Results: 3,2000-01-01 09:27:25.00,327150000,-1170969500,,,49960,1010,,,,,,8,[29,21,26,15,18,9,6,10,7,], 136 | 137 | Input: $GPGGA,092725.00,3242.9000,N,11705.8171,W,1,8,1.01,499.6,M,48.0,M,,0*40 138 | Results: 3,2000-01-01 09:27:25.00,327150000,-1170969517,,,49960,1010,,,,,,8,[29,21,26,15,18,9,6,10,7,], 139 | 140 | Input: $GPGGA,092725.00,3242.9000,N,11705.8172,W,1,8,1.01,499.6,M,48.0,M,,0*43 141 | Results: 3,2000-01-01 09:27:25.00,327150000,-1170969533,,,49960,1010,,,,,,8,[29,21,26,15,18,9,6,10,7,], 142 | 143 | Input: $GPGGA,092725.00,3242.9000,N,11705.8173,W,1,8,1.01,499.6,M,48.0,M,,0*42 144 | Results: 3,2000-01-01 09:27:25.00,327150000,-1170969550,,,49960,1010,,,,,,8,[29,21,26,15,18,9,6,10,7,], 145 | 146 | Input: $GPGGA,092725.00,3242.9000,N,11705.8174,W,1,8,1.01,499.6,M,48.0,M,,0*45 147 | Results: 3,2000-01-01 09:27:25.00,327150000,-1170969567,,,49960,1010,,,,,,8,[29,21,26,15,18,9,6,10,7,], 148 | 149 | Input: $GPGGA,092725.00,3242.9000,N,11705.8175,W,1,8,1.01,499.6,M,48.0,M,,0*44 150 | Results: 3,2000-01-01 09:27:25.00,327150000,-1170969583,,,49960,1010,,,,,,8,[29,21,26,15,18,9,6,10,7,], 151 | 152 | Input: $GPGGA,092725.00,3242.9000,N,11705.8176,W,1,8,1.01,499.6,M,48.0,M,,0*47 153 | Results: 3,2000-01-01 09:27:25.00,327150000,-1170969600,,,49960,1010,,,,,,8,[29,21,26,15,18,9,6,10,7,], 154 | ``` 155 | 156 | ### Benchmark 157 | 158 | * [NMEAbenchmark](/examples/NMEAbenchmark/NMEAbenchmark.ino) 159 | 160 | For this program, **No GPS device is required**. GGA, RMC and GSV sentences can be tested. Bytes are streamed from PROGMEM character arrays and parsed to determine execution times. All times are displayed in microseconds: 161 | 162 | ``` 163 | NMEAbenchmark: started 164 | fix object size = 22 165 | NMEAGPS object size = 29 166 | GGA time = 844 167 | GGA no lat time = 497 168 | ``` 169 | -------------------------------------------------------------------------------- /examples/NMEAorder/NMEAorder.ino: -------------------------------------------------------------------------------- 1 | #include 2 | 3 | //====================================================================== 4 | // Program: NMEAorder.ino 5 | // 6 | // Description: This example program records the order of sentences 7 | // received in each 1-second interval. The last sentence is 8 | // important to know, as that will be used to determine when the 9 | // GPS quiet time is starting (see NMEA.ino). It is safe to perform 10 | // time-consuming operations at that point, and the risk of losing 11 | // characters will be minimized (see comments in 'GPSloop'). 12 | // 13 | // Prerequisites: 14 | // 1) Your GPS device has been correctly powered. 15 | // Be careful when connecting 3.3V devices. 16 | // 2) Your GPS device is correctly connected to an Arduino serial port. 17 | // See GPSport.h for the default connections. 18 | // 3) You know the default baud rate of your GPS device 19 | // Use NMEAdiagnostic.ino to scan for the correct baud rate. 20 | // 4) NMEAGPS_RECOGNIZE_ALL must be enabled in NMEAGPS_cfg.h 21 | // 22 | // 'Serial' is for debug output to the Serial Monitor window. 23 | // 24 | // License: 25 | // Copyright (C) 2014-2017, SlashDevin 26 | // 27 | // This file is part of NeoGPS 28 | // 29 | // NeoGPS is free software: you can redistribute it and/or modify 30 | // it under the terms of the GNU General Public License as published by 31 | // the Free Software Foundation, either version 3 of the License, or 32 | // (at your option) any later version. 33 | // 34 | // NeoGPS is distributed in the hope that it will be useful, 35 | // but WITHOUT ANY WARRANTY; without even the implied warranty of 36 | // MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the 37 | // GNU General Public License for more details. 38 | // 39 | // You should have received a copy of the GNU General Public License 40 | // along with NeoGPS. If not, see . 41 | // 42 | //====================================================================== 43 | 44 | #include 45 | 46 | //------------------------------------------------------------ 47 | // Check configuration 48 | 49 | #ifndef NMEAGPS_RECOGNIZE_ALL 50 | #error You must define NMEAGPS_RECOGNIZE_ALL in NMEAGPS_cfg.h! 51 | #endif 52 | 53 | #ifdef NMEAGPS_INTERRUPT_PROCESSING 54 | #error You must *NOT* define NMEAGPS_INTERRUPT_PROCESSING in NMEAGPS_cfg.h! 55 | #endif 56 | 57 | static NMEAGPS gps ; // This parses received characters 58 | static uint32_t last_rx = 0L; // The last millis() time a character was 59 | // received from GPS. This is used to 60 | // determine when the GPS quiet time begins. 61 | 62 | //------------------------------------------------------------ 63 | 64 | static NMEAGPS::nmea_msg_t last_sentence_in_interval = NMEAGPS::NMEA_UNKNOWN; 65 | static uint8_t prev_sentence_count = 0; 66 | static uint8_t sentence_count = 0; 67 | static const uint8_t MAX_SENTENCES = 20; // per second 68 | static NMEAGPS::nmea_msg_t sentences[ MAX_SENTENCES ]; 69 | 70 | static void recordSentenceTypes() 71 | { 72 | // Always save the last sentence, even if we're full 73 | sentences[ sentence_count ] = gps.nmeaMessage; 74 | if (sentence_count < MAX_SENTENCES-1) 75 | sentence_count++; 76 | 77 | } // recordSentenceTypes 78 | 79 | //----------------------------------------------------------- 80 | 81 | static void printSentenceOrder() 82 | { 83 | DEBUG_PORT.println( F("\nSentence order in each 1-second interval:") ); 84 | 85 | for (uint8_t i=0; i 5) { 138 | 139 | // The GPS device has not sent any characters for at least 5ms. 140 | // See if we've been getting chars sometime during the last second. 141 | // If not, the GPS may not be working or connected properly. 142 | 143 | bool getting_chars = (ms_since_last_rx < 1000UL); 144 | static uint32_t last_quiet_time = 0UL; 145 | bool just_went_quiet = 146 | (((int32_t) (last_rx - last_quiet_time)) > 10L); 147 | bool next_quiet_time = 148 | ((current_ms - last_quiet_time) >= 1000UL); 149 | 150 | if ((getting_chars && just_went_quiet) 151 | || 152 | (!getting_chars && next_quiet_time)) { 153 | 154 | last_quiet_time = current_ms; // Remember for next loop 155 | 156 | // If we're not getting good data, make some suggestions. 157 | 158 | bool allDone = false; 159 | 160 | if (!getting_chars) { 161 | 162 | DEBUG_PORT.println( F("\nCheck GPS device and/or connections. No characters received.\n") ); 163 | 164 | allDone = true; 165 | 166 | } else if (sentence_count == 0) { 167 | 168 | DEBUG_PORT.println( F("No valid sentences, but characters are being received.\n" 169 | "Check baud rate or device protocol configuration.\n" ) ); 170 | 171 | allDone = true; 172 | } 173 | 174 | if (allDone) { 175 | DEBUG_PORT.print( F("\nEND.\n") ); 176 | for (;;) 177 | ; // hang! 178 | } 179 | 180 | // No problem, just a real GPS quiet time. 181 | return true; 182 | } 183 | } 184 | 185 | return false; 186 | 187 | } // quietTimeStarted 188 | 189 | //---------------------------------------------------------------- 190 | // Figure out what sentence the GPS device sends 191 | // as the last sentence in each 1-second interval. 192 | 193 | static void watchForLastSentence() 194 | { 195 | if (quietTimeStarted()) { 196 | 197 | if (prev_sentence_count != sentence_count) { 198 | 199 | // We have NOT received two full intervals of sentences with 200 | // the same number of sentences in each interval. Start 201 | // recording again. 202 | prev_sentence_count = sentence_count; 203 | sentence_count = 0; 204 | 205 | } else if (sentence_count > 0) { 206 | 207 | // Got it! 208 | last_sentence_in_interval = sentences[ sentence_count-1 ]; 209 | } 210 | } 211 | 212 | } // watchForLastSentence 213 | 214 | //-------------------------- 215 | 216 | void setup() 217 | { 218 | DEBUG_PORT.begin(9600); 219 | while (!DEBUG_PORT) 220 | ; 221 | 222 | DEBUG_PORT.print( F("NMEAorder.INO: started\n") ); 223 | DEBUG_PORT.print( F("fix object size = ") ); 224 | DEBUG_PORT.println( sizeof(gps.fix()) ); 225 | DEBUG_PORT.print( F("NMEAGPS object size = ") ); 226 | DEBUG_PORT.println( sizeof(gps) ); 227 | DEBUG_PORT.println( F("Looking for GPS device on " GPS_PORT_NAME) ); 228 | DEBUG_PORT.flush(); 229 | 230 | gpsPort.begin( 9600 ); 231 | } 232 | 233 | //-------------------------- 234 | 235 | void loop() 236 | { 237 | GPSloop(); 238 | 239 | if (last_sentence_in_interval == NMEAGPS::NMEA_UNKNOWN) 240 | watchForLastSentence(); 241 | else { 242 | 243 | printSentenceOrder(); 244 | for (;;) 245 | ; // All done! 246 | } 247 | } 248 | -------------------------------------------------------------------------------- /src/NeoTime.h: -------------------------------------------------------------------------------- 1 | #ifndef TIME_H 2 | #define TIME_H 3 | 4 | // Copyright (C) 2014-2017, SlashDevin 5 | // 6 | // This file is part of NeoGPS 7 | // 8 | // NeoGPS is free software: you can redistribute it and/or modify 9 | // it under the terms of the GNU General Public License as published by 10 | // the Free Software Foundation, either version 3 of the License, or 11 | // (at your option) any later version. 12 | // 13 | // NeoGPS is distributed in the hope that it will be useful, 14 | // but WITHOUT ANY WARRANTY; without even the implied warranty of 15 | // MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the 16 | // GNU General Public License for more details. 17 | // 18 | // You should have received a copy of the GNU General Public License 19 | // along with NeoGPS. If not, see . 20 | 21 | #include "NeoGPS_cfg.h" 22 | #include "CosaCompat.h" 23 | 24 | namespace NeoGPS { 25 | 26 | //------------------------------------------------------ 27 | // Enable/disable run-time modification of the epoch. 28 | // If this is defined, epoch mutators are available. 29 | // If this is not defined, the epoch is a hard-coded constant. 30 | // Only epoch accessors are available. 31 | //#define TIME_EPOCH_MODIFIABLE 32 | 33 | /** 34 | * Number of seconds elapsed since January 1 of the Epoch Year, 35 | * 00:00:00 +0000 (UTC). 36 | */ 37 | typedef uint32_t clock_t; 38 | 39 | const uint8_t SECONDS_PER_MINUTE = 60; 40 | const uint8_t MINUTES_PER_HOUR = 60; 41 | const uint16_t SECONDS_PER_HOUR = (uint16_t) SECONDS_PER_MINUTE * MINUTES_PER_HOUR; 42 | const uint8_t HOURS_PER_DAY = 24; 43 | const uint32_t SECONDS_PER_DAY = (uint32_t) SECONDS_PER_HOUR * HOURS_PER_DAY; 44 | const uint8_t DAYS_PER_WEEK = 7; 45 | 46 | /** 47 | * Common date/time structure 48 | */ 49 | struct time_t { 50 | 51 | enum weekday_t { 52 | SUNDAY = 1, 53 | MONDAY = 2, 54 | TUESDAY = 3, 55 | WEDNESDAY = 4, 56 | THURSDAY = 5, 57 | FRIDAY = 6, 58 | SATURDAY = 7 59 | }; 60 | 61 | // NTP epoch year and weekday (Monday) 62 | static const uint16_t NTP_EPOCH_YEAR = 1900; 63 | static const uint8_t NTP_EPOCH_WEEKDAY = MONDAY; 64 | 65 | // POSIX epoch year and weekday (Thursday) 66 | static const uint16_t POSIX_EPOCH_YEAR = 1970; 67 | static const uint8_t POSIX_EPOCH_WEEKDAY = THURSDAY; 68 | 69 | // Y2K epoch year and weekday (Saturday) 70 | static const uint16_t Y2K_EPOCH_YEAR = 2000; 71 | static const uint8_t Y2K_EPOCH_WEEKDAY = SATURDAY; 72 | 73 | uint8_t seconds; //!< 00-59 74 | uint8_t minutes; //!< 00-59 75 | uint8_t hours; //!< 00-23 76 | uint8_t day; //!< 01-07 Day of Week 77 | uint8_t date; //!< 01-31 Day of Month 78 | uint8_t month; //!< 01-12 79 | uint8_t year; //!< 00-99 80 | 81 | /** 82 | * Constructor. 83 | */ 84 | time_t() {} 85 | 86 | /** 87 | * Construct from seconds since the Epoch. 88 | * @param[in] c clock. 89 | */ 90 | time_t(clock_t c); 91 | 92 | /** 93 | * Initialize to January 1 of the Epoch Year, 00:00:00 94 | */ 95 | void init(); 96 | 97 | /** 98 | * Convert to seconds. 99 | * @return seconds from epoch. 100 | */ 101 | operator clock_t() const; 102 | 103 | /** 104 | * Offset by a number of seconds. 105 | * @param[in] offset in seconds. 106 | */ 107 | void operator +=( clock_t offset ) 108 | { *this = offset + operator clock_t(); } 109 | 110 | /** 111 | * Set day member from current value. This is a relatively expensive 112 | * operation, so the weekday is only calculated when requested. 113 | */ 114 | void set_day() 115 | { 116 | day = weekday_for(days()); 117 | } 118 | 119 | /** 120 | * Convert to days. 121 | * @return days from January 1 of the epoch year. 122 | */ 123 | uint16_t days() const; 124 | 125 | /** 126 | * Calculate day of the current year. 127 | * @return days from January 1, which is day zero. 128 | */ 129 | uint16_t day_of_year() const; 130 | 131 | /** 132 | * Calculate 4-digit year from internal 2-digit year member. 133 | * @return 4-digit year. 134 | */ 135 | uint16_t full_year() const 136 | { 137 | return full_year(year); 138 | } 139 | 140 | /** 141 | * Calculate 4-digit year from a 2-digit year 142 | * @param[in] year (4-digit). 143 | * @return true if /year/ is a leap year. 144 | */ 145 | static uint16_t full_year( uint8_t year ) 146 | { 147 | uint16_t y = year; 148 | 149 | if (y < pivot_year()) 150 | y += 100 * (epoch_year()/100 + 1); 151 | else 152 | y += 100 * (epoch_year()/100); 153 | 154 | return y; 155 | } 156 | 157 | /** 158 | * Determine whether the current year is a leap year. 159 | * @returns true if the two-digit /year/ member is a leap year. 160 | */ 161 | bool is_leap() const 162 | { 163 | return is_leap(full_year()); 164 | } 165 | 166 | /** 167 | * Determine whether the 4-digit /year/ is a leap year. 168 | * @param[in] year (4-digit). 169 | * @return true if /year/ is a leap year. 170 | */ 171 | static bool is_leap(uint16_t year) 172 | { 173 | if (year % 4) return false; 174 | uint16_t y = year % 400; 175 | return (y == 0) || ((y != 100) && (y != 200) && (y != 300)); 176 | } 177 | 178 | /** 179 | * Calculate how many days are in the specified year. 180 | * @param[in] year (4-digit). 181 | * @return number of days. 182 | */ 183 | static uint16_t days_per(uint16_t year) 184 | { 185 | return (365 + is_leap(year)); 186 | } 187 | 188 | /** 189 | * Determine the day of the week for the specified day number 190 | * @param[in] dayno number as counted from January 1 of the epoch year. 191 | * @return weekday number 1..7, as for the /day/ member. 192 | */ 193 | static uint8_t weekday_for(uint16_t dayno) 194 | { 195 | return ((dayno+epoch_weekday()-1) % DAYS_PER_WEEK) + 1; 196 | } 197 | 198 | /** 199 | * Check that all members, EXCEPT FOR day, are set to a coherent date/time. 200 | * @return true if valid date/time. 201 | */ 202 | bool is_valid() const 203 | { 204 | return 205 | ((year <= 99) && 206 | (1 <= month) && (month <= 12) && 207 | ((1 <= date) && 208 | ((date <= pgm_read_byte(&days_in[month])) || 209 | ((month == 2) && is_leap() && (date == 29)))) && 210 | (hours <= 23) && 211 | (minutes <= 59) && 212 | (seconds <= 59)); 213 | } 214 | 215 | /** 216 | * Set the epoch year for all time_t operations. Note that the pivot 217 | * year defaults to the epoch_year % 100. Valid years will be in the 218 | * range epoch_year..epoch_year+99. Selecting a different pivot year 219 | * will slide this range to the right. 220 | * @param[in] y epoch year to set. 221 | * See also /full_year/. 222 | */ 223 | #ifdef TIME_EPOCH_MODIFIABLE 224 | static void epoch_year(uint16_t y) 225 | { 226 | s_epoch_year = y; 227 | epoch_offset( s_epoch_year % 100 ); 228 | pivot_year( epoch_offset() ); 229 | } 230 | #endif 231 | 232 | /** 233 | * Get the epoch year. 234 | * @return year. 235 | */ 236 | static uint16_t epoch_year() 237 | { 238 | return (s_epoch_year); 239 | } 240 | 241 | static uint8_t epoch_weekday() { return s_epoch_weekday; }; 242 | #ifdef TIME_EPOCH_MODIFIABLE 243 | static void epoch_weekday( uint8_t ew ) { s_epoch_weekday = ew; }; 244 | #endif 245 | 246 | /** 247 | * The pivot year determine the range of years WRT the epoch_year 248 | * For example, an epoch year of 2000 and a pivot year of 80 will 249 | * allow years in the range 1980 to 2079. Default 0 for Y2K_EPOCH. 250 | */ 251 | static uint8_t pivot_year() { return s_pivot_year; }; 252 | #ifdef TIME_EPOCH_MODIFIABLE 253 | static void pivot_year( uint8_t py ) { s_pivot_year = py; }; 254 | #endif 255 | 256 | #ifdef TIME_EPOCH_MODIFIABLE 257 | /** 258 | * Use the current year for the epoch year. This will result in the 259 | * best performance of conversions, but dates/times before January 1 260 | * of the epoch year cannot be represented. 261 | */ 262 | static void use_fastest_epoch(); 263 | #endif 264 | 265 | /** 266 | * Parse a character string and fill out members. 267 | * @param[in] s PROGMEM character string with format "YYYY-MM-DD HH:MM:SS". 268 | * @return success. 269 | */ 270 | bool parse(str_P s); 271 | 272 | static const uint8_t days_in[] PROGMEM; // month index is 1..12, PROGMEM 273 | 274 | protected: 275 | static uint8_t epoch_offset() { return s_epoch_offset; }; 276 | 277 | #ifdef TIME_EPOCH_MODIFIABLE 278 | static void epoch_offset( uint8_t eo ) { s_epoch_offset = eo; }; 279 | 280 | static uint16_t s_epoch_year; 281 | static uint8_t s_pivot_year; 282 | static uint8_t s_epoch_offset; 283 | static uint8_t s_epoch_weekday; 284 | #else 285 | static const uint16_t s_epoch_year = Y2K_EPOCH_YEAR; 286 | static const uint8_t s_pivot_year = s_epoch_year % 100; 287 | static const uint8_t s_epoch_offset = s_pivot_year; 288 | static const uint8_t s_epoch_weekday = Y2K_EPOCH_WEEKDAY; 289 | #endif 290 | 291 | } NEOGPS_PACKED; 292 | 293 | }; // namespace NeoGPS 294 | 295 | class Print; 296 | 297 | /** 298 | * Print the date/time to the given stream with the format "YYYY-MM-DD HH:MM:SS". 299 | * @param[in] outs output stream. 300 | * @param[in] t time structure. 301 | * @return iostream. 302 | */ 303 | Print & operator <<( Print & outs, const NeoGPS::time_t &t ); 304 | 305 | #endif 306 | --------------------------------------------------------------------------------