mirror of https://github.com/ArduPilot/ardupilot
The previous initialisation strategy for auto-detection doesn't play well with the way APM uses the GPS.
Switch to subclassing GPS and manipulating a global pointer. Update the test program so that it works again. git-svn-id: https://arducopter.googlecode.com/svn/trunk@673 f9c3cf11-9bcb-44bc-f272-b75c42450872
This commit is contained in:
parent
ca6d51cddb
commit
ee105a0ebf
|
@ -10,8 +10,18 @@
|
||||||
|
|
||||||
static unsigned int baudrates[] = {38400U, 57600U, 9600U, 4800U};
|
static unsigned int baudrates[] = {38400U, 57600U, 9600U, 4800U};
|
||||||
|
|
||||||
GPS *
|
void
|
||||||
AP_GPS_Auto::detect(void)
|
AP_GPS_Auto::init(void)
|
||||||
|
{
|
||||||
|
}
|
||||||
|
|
||||||
|
//
|
||||||
|
// Called the first time that a client tries to kick the GPS to update.
|
||||||
|
//
|
||||||
|
// We detect the real GPS, then update the pointer we have been called through
|
||||||
|
// and return.
|
||||||
|
void
|
||||||
|
AP_GPS_Auto::update(void)
|
||||||
{
|
{
|
||||||
GPS *gps;
|
GPS *gps;
|
||||||
int i;
|
int i;
|
||||||
|
@ -20,10 +30,21 @@ AP_GPS_Auto::detect(void)
|
||||||
for (;;) {
|
for (;;) {
|
||||||
// loop through possible baudrates
|
// loop through possible baudrates
|
||||||
for (i = 0; i < (sizeof(baudrates) / sizeof(baudrates[0])); i++) {
|
for (i = 0; i < (sizeof(baudrates) / sizeof(baudrates[0])); i++) {
|
||||||
printf("autodetect at %d:%u\n", i, baudrates[i]);
|
printf("GPS autodetect at %d:%u\n", i, baudrates[i]);
|
||||||
_port->begin(baudrates[i]);
|
_port->begin(baudrates[i]);
|
||||||
if (NULL != (gps = _detect()))
|
if (NULL != (gps = _detect())) {
|
||||||
return(gps);
|
// make the detected GPS the default
|
||||||
|
*_gps = gps;
|
||||||
|
|
||||||
|
// configure the detected GPS and run one update
|
||||||
|
gps->print_errors = true; // XXX
|
||||||
|
gps->init();
|
||||||
|
gps->update();
|
||||||
|
|
||||||
|
// drop back to our caller - subsequent calls through
|
||||||
|
// the global will not come here
|
||||||
|
return;
|
||||||
|
}
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
@ -129,12 +150,6 @@ AP_GPS_Auto::_detect(void)
|
||||||
break;
|
break;
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
// If we detected a GPS, call its init routine
|
|
||||||
if (NULL != gps) {
|
|
||||||
gps->print_errors = true; // XXX
|
|
||||||
gps->init();
|
|
||||||
}
|
|
||||||
return(gps);
|
return(gps);
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
|
@ -9,7 +9,7 @@
|
||||||
#include <GPS.h>
|
#include <GPS.h>
|
||||||
#include <FastSerial.h>
|
#include <FastSerial.h>
|
||||||
|
|
||||||
class AP_GPS_Auto
|
class AP_GPS_Auto : public GPS
|
||||||
{
|
{
|
||||||
public:
|
public:
|
||||||
/// Constructor
|
/// Constructor
|
||||||
|
@ -21,17 +21,26 @@ public:
|
||||||
/// @param ptr Pointer to a GPS * that will be fixed up by ::init
|
/// @param ptr Pointer to a GPS * that will be fixed up by ::init
|
||||||
/// when the GPS type has been detected.
|
/// when the GPS type has been detected.
|
||||||
///
|
///
|
||||||
AP_GPS_Auto(FastSerial *port = NULL) : _port(port) {};
|
AP_GPS_Auto(FastSerial *port, GPS **gps) :
|
||||||
|
_port(port),
|
||||||
|
_gps(gps)
|
||||||
|
{};
|
||||||
|
|
||||||
|
void init(void);
|
||||||
|
|
||||||
/// 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.
|
||||||
///
|
///
|
||||||
GPS *detect(void);
|
void update(void);
|
||||||
|
|
||||||
private:
|
private:
|
||||||
/// Serial port connected to the GPS.
|
/// Serial port connected to the GPS.
|
||||||
FastSerial *_port;
|
FastSerial *_port;
|
||||||
|
|
||||||
|
/// global GPS driver pointer, updated by auto-detection
|
||||||
|
///
|
||||||
|
GPS **_gps;
|
||||||
|
|
||||||
/// low-level auto-detect routine
|
/// low-level auto-detect routine
|
||||||
///
|
///
|
||||||
GPS *_detect(void);
|
GPS *_detect(void);
|
||||||
|
|
|
@ -4,23 +4,30 @@
|
||||||
|
|
||||||
#include <FastSerial.h>
|
#include <FastSerial.h>
|
||||||
#include <AP_GPS.h>
|
#include <AP_GPS.h>
|
||||||
|
#include <stdlib.h>
|
||||||
|
|
||||||
FastSerialPort0(Serial);
|
FastSerialPort0(Serial);
|
||||||
FastSerialPort1(Serial1);
|
FastSerialPort1(Serial1);
|
||||||
|
|
||||||
GPS *gps;
|
GPS *gps;
|
||||||
AP_GPS_Auto GPS(&Serial1);
|
AP_GPS_Auto GPS(&Serial1, &gps);
|
||||||
|
|
||||||
#define T6 1000000
|
#define T6 1000000
|
||||||
#define T7 10000000
|
#define T7 10000000
|
||||||
|
|
||||||
|
void * operator new(size_t size)
|
||||||
|
{
|
||||||
|
return(calloc(size, 1));
|
||||||
|
}
|
||||||
|
|
||||||
void setup()
|
void setup()
|
||||||
{
|
{
|
||||||
Serial.begin(38400);
|
Serial.begin(38400);
|
||||||
Serial1.begin(38400);
|
Serial1.begin(38400);
|
||||||
|
|
||||||
Serial.println("GPS AUTO library test");
|
Serial.println("GPS AUTO library test");
|
||||||
gps = GPS.detect(); // GPS Initialization
|
gps = &GPS;
|
||||||
|
gps->init();
|
||||||
delay(1000);
|
delay(1000);
|
||||||
}
|
}
|
||||||
void loop()
|
void loop()
|
||||||
|
|
Loading…
Reference in New Issue