mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-21 07:13:56 -04:00
AP_GPS libs now recover from disconnect or failed initialization.
git-svn-id: https://arducopter.googlecode.com/svn/trunk@1188 f9c3cf11-9bcb-44bc-f272-b75c42450872
This commit is contained in:
parent
a257c51a09
commit
aa115aea68
@ -21,7 +21,7 @@ AP_GPS_Auto::init(void)
|
|||||||
// We detect the real GPS, then update the pointer we have been called through
|
// We detect the real GPS, then update the pointer we have been called through
|
||||||
// and return.
|
// and return.
|
||||||
void
|
void
|
||||||
AP_GPS_Auto::update(void)
|
AP_GPS_Auto::read(void)
|
||||||
{
|
{
|
||||||
GPS *gps;
|
GPS *gps;
|
||||||
int i;
|
int i;
|
||||||
|
@ -31,7 +31,7 @@ public:
|
|||||||
/// Detect and initialise the attached GPS unit. Returns a
|
/// Detect and initialise the attached GPS unit. Returns a
|
||||||
/// pointer to the allocated & initialised GPS driver.
|
/// pointer to the allocated & initialised GPS driver.
|
||||||
///
|
///
|
||||||
void update(void);
|
void read(void);
|
||||||
|
|
||||||
private:
|
private:
|
||||||
/// Serial port connected to the GPS.
|
/// Serial port connected to the GPS.
|
||||||
|
@ -24,7 +24,7 @@ void AP_GPS_HIL::init(void)
|
|||||||
{
|
{
|
||||||
}
|
}
|
||||||
|
|
||||||
void AP_GPS_HIL::update(void)
|
void AP_GPS_HIL::read(void)
|
||||||
{
|
{
|
||||||
}
|
}
|
||||||
|
|
||||||
|
@ -18,7 +18,7 @@ class AP_GPS_HIL : public GPS {
|
|||||||
public:
|
public:
|
||||||
AP_GPS_HIL(Stream *s);
|
AP_GPS_HIL(Stream *s);
|
||||||
void init(void);
|
void init(void);
|
||||||
void update(void);
|
void read(void);
|
||||||
int status(void);
|
int status(void);
|
||||||
/**
|
/**
|
||||||
* Hardware in the loop set function
|
* Hardware in the loop set function
|
||||||
|
@ -22,6 +22,7 @@ AP_GPS_MTK::AP_GPS_MTK(Stream *s) : GPS(s)
|
|||||||
// Public Methods //////////////////////////////////////////////////////////////
|
// Public Methods //////////////////////////////////////////////////////////////
|
||||||
void AP_GPS_MTK::init(void)
|
void AP_GPS_MTK::init(void)
|
||||||
{
|
{
|
||||||
|
delay(1000);
|
||||||
_port->flush();
|
_port->flush();
|
||||||
// initialize serial port for binary protocol use
|
// initialize serial port for binary protocol use
|
||||||
// XXX should assume binary, let GPS_AUTO handle dynamic config?
|
// XXX should assume binary, let GPS_AUTO handle dynamic config?
|
||||||
@ -42,7 +43,7 @@ void AP_GPS_MTK::init(void)
|
|||||||
// The lack of a standard header length field makes it impossible to skip
|
// The lack of a standard header length field makes it impossible to skip
|
||||||
// unrecognised messages.
|
// unrecognised messages.
|
||||||
//
|
//
|
||||||
void AP_GPS_MTK::update(void)
|
void AP_GPS_MTK::read(void)
|
||||||
{
|
{
|
||||||
byte data;
|
byte data;
|
||||||
int numc;
|
int numc;
|
||||||
|
@ -37,7 +37,7 @@ class AP_GPS_MTK : public GPS {
|
|||||||
public:
|
public:
|
||||||
AP_GPS_MTK(Stream *s);
|
AP_GPS_MTK(Stream *s);
|
||||||
virtual void init(void);
|
virtual void init(void);
|
||||||
virtual void update(void);
|
virtual void read(void);
|
||||||
|
|
||||||
private:
|
private:
|
||||||
#pragma pack(1)
|
#pragma pack(1)
|
||||||
|
@ -18,7 +18,7 @@
|
|||||||
|
|
||||||
Methods:
|
Methods:
|
||||||
init() : GPS Initialization
|
init() : GPS Initialization
|
||||||
update() : Call this funcion as often as you want to ensure you read the incomming gps data
|
read() : Call this funcion as often as you want to ensure you read the incomming gps data
|
||||||
|
|
||||||
Properties:
|
Properties:
|
||||||
latitude : latitude * 10000000 (long value)
|
latitude : latitude * 10000000 (long value)
|
||||||
@ -63,7 +63,7 @@ AP_GPS_NMEA::init(void)
|
|||||||
// We can call this function on the main loop (50Hz loop)
|
// We can call this function on the main loop (50Hz loop)
|
||||||
// If we get a complete packet this function call parse_nmea_gps() to parse and update the GPS info.
|
// If we get a complete packet this function call parse_nmea_gps() to parse and update the GPS info.
|
||||||
void
|
void
|
||||||
AP_GPS_NMEA::update(void)
|
AP_GPS_NMEA::read(void)
|
||||||
{
|
{
|
||||||
char c;
|
char c;
|
||||||
int numc;
|
int numc;
|
||||||
|
@ -37,7 +37,7 @@ class AP_GPS_NMEA : public GPS
|
|||||||
// Methods
|
// Methods
|
||||||
AP_GPS_NMEA(Stream *s);
|
AP_GPS_NMEA(Stream *s);
|
||||||
void init();
|
void init();
|
||||||
void update();
|
void read();
|
||||||
|
|
||||||
// Properties
|
// Properties
|
||||||
uint8_t quality; // GPS Signal quality
|
uint8_t quality; // GPS Signal quality
|
||||||
|
@ -50,7 +50,7 @@ void AP_GPS_SIRF::init(void)
|
|||||||
// re-processing it from the top, this is unavoidable. The parser
|
// re-processing it from the top, this is unavoidable. The parser
|
||||||
// attempts to avoid this when possible.
|
// attempts to avoid this when possible.
|
||||||
//
|
//
|
||||||
void AP_GPS_SIRF::update(void)
|
void AP_GPS_SIRF::read(void)
|
||||||
{
|
{
|
||||||
byte data;
|
byte data;
|
||||||
int numc;
|
int numc;
|
||||||
|
@ -20,7 +20,7 @@ public:
|
|||||||
AP_GPS_SIRF(Stream *s);
|
AP_GPS_SIRF(Stream *s);
|
||||||
|
|
||||||
virtual void init();
|
virtual void init();
|
||||||
virtual void update();
|
virtual void read();
|
||||||
|
|
||||||
private:
|
private:
|
||||||
#pragma pack(1)
|
#pragma pack(1)
|
||||||
|
@ -37,7 +37,7 @@ void AP_GPS_UBLOX::init(void)
|
|||||||
// re-processing it from the top, this is unavoidable. The parser
|
// re-processing it from the top, this is unavoidable. The parser
|
||||||
// attempts to avoid this when possible.
|
// attempts to avoid this when possible.
|
||||||
//
|
//
|
||||||
void AP_GPS_UBLOX::update(void)
|
void AP_GPS_UBLOX::read(void)
|
||||||
{
|
{
|
||||||
byte data;
|
byte data;
|
||||||
int numc;
|
int numc;
|
||||||
|
@ -21,7 +21,7 @@ public:
|
|||||||
// Methods
|
// Methods
|
||||||
AP_GPS_UBLOX(Stream *s = NULL);
|
AP_GPS_UBLOX(Stream *s = NULL);
|
||||||
void init(void);
|
void init(void);
|
||||||
void update();
|
void read();
|
||||||
|
|
||||||
private:
|
private:
|
||||||
// u-blox UBX protocol essentials
|
// u-blox UBX protocol essentials
|
||||||
|
@ -20,3 +20,18 @@ GPS::_setTime(void)
|
|||||||
{
|
{
|
||||||
_lastTime = millis();
|
_lastTime = millis();
|
||||||
}
|
}
|
||||||
|
|
||||||
|
void
|
||||||
|
GPS::update(void)
|
||||||
|
{
|
||||||
|
if (!status())
|
||||||
|
{
|
||||||
|
Serial.println("Reinitializing GPS");
|
||||||
|
init();
|
||||||
|
_setTime();
|
||||||
|
}
|
||||||
|
else
|
||||||
|
{
|
||||||
|
read();
|
||||||
|
}
|
||||||
|
}
|
||||||
|
@ -44,7 +44,10 @@ public:
|
|||||||
///
|
///
|
||||||
/// Must be implemented by the GPS driver.
|
/// Must be implemented by the GPS driver.
|
||||||
///
|
///
|
||||||
virtual void update(void) = 0;
|
void update(void);
|
||||||
|
|
||||||
|
/// Implement specific routines for gps to receive a message.
|
||||||
|
virtual void read(void) = 0;
|
||||||
|
|
||||||
/// Query GPS status
|
/// Query GPS status
|
||||||
///
|
///
|
||||||
|
Loading…
Reference in New Issue
Block a user