• Main Page
  • Related Pages
  • Namespaces
  • Classes
  • Files
  • File List
  • File Members

GPS.cpp

Go to the documentation of this file.
00001 // -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: t -*-
00002 
00003 #include "GPS.h"
00004 #include "WProgram.h"
00005 
00006 void
00007 GPS::update(void)
00008 {
00009         bool    result;
00010 
00011         // call the GPS driver to process incoming data
00012         result = read();
00013 
00014         // if we did not get a message, and the idle timer has expired, re-init
00015         if (!result) {
00016                 if ((millis() - _idleTimer) > _idleTimeout) {
00017                         _status = NO_GPS;
00018                         init();
00019                 }
00020         } else {
00021                 // we got a message, update our status correspondingly
00022                 _status = fix ? GPS_OK : NO_FIX;
00023 
00024                 valid_read = true;
00025                 new_data = true;
00026         }
00027 
00028         // reset the idle timer
00029         _idleTimer = millis();
00030 }
00031 
00032 // XXX this is probably the wrong way to do it, too
00033 void
00034 GPS::_error(const char *msg)
00035 {
00036         Serial.println(msg);
00037 }

Generated for ArduPilot Libraries by doxygen