mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 22:48:29 -04:00
7fc6515300
Nuke AP_GPS_IMU, as nothing is using it anymore. Simplify the handling of no GPS/no fix detection. Fix prototypes for ::init and ::read. Update AP_GPS_Auto and corresponding example, nearly ready for primetime. Use uint8_t rather than byte. Strip some _error() calls to save space. More could still go. git-svn-id: https://arducopter.googlecode.com/svn/trunk@1246 f9c3cf11-9bcb-44bc-f272-b75c42450872
38 lines
708 B
C++
38 lines
708 B
C++
// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: t -*-
|
|
|
|
#include "GPS.h"
|
|
#include "WProgram.h"
|
|
|
|
void
|
|
GPS::update(void)
|
|
{
|
|
bool result;
|
|
|
|
// call the GPS driver to process incoming data
|
|
result = read();
|
|
|
|
// if we did not get a message, and the idle timer has expired, re-init
|
|
if (!result) {
|
|
if ((millis() - _idleTimer) > _idleTimeout) {
|
|
_status = NO_GPS;
|
|
init();
|
|
}
|
|
} else {
|
|
// we got a message, update our status correspondingly
|
|
_status = fix ? GPS_OK : NO_FIX;
|
|
|
|
valid_read = true;
|
|
new_data = true;
|
|
}
|
|
|
|
// reset the idle timer
|
|
_idleTimer = millis();
|
|
}
|
|
|
|
// XXX this is probably the wrong way to do it, too
|
|
void
|
|
GPS::_error(const char *msg)
|
|
{
|
|
Serial.println(msg);
|
|
}
|