AP_GPS: added DataFlash to GPS init to allow for detailed logging

this will allow GPS drivers to log much more detailed device specific
information
This commit is contained in:
Andrew Tridgell 2014-03-24 12:01:13 +11:00
parent d124fdb182
commit 7ff293ca38
22 changed files with 38 additions and 42 deletions

View File

@ -28,12 +28,12 @@ extern const AP_HAL::HAL& hal;
static const char init_str[] = "$PSRF100,0,57600,8,1,0*37";
// Public Methods ////////////////////////////////////////////////////////////////////
void AP_GPS_406::init(AP_HAL::UARTDriver *s, enum GPS_Engine_Setting nav_setting)
void AP_GPS_406::init(AP_HAL::UARTDriver *s, enum GPS_Engine_Setting nav_setting, DataFlash_Class *DataFlash)
{
_change_to_sirf_protocol(); // Changes to SIRF protocol and sets baud rate
_configure_gps(); // Function to configure GPS, to output only the desired msg's
AP_GPS_SIRF::init(s, nav_setting); // let the superclass do anything it might need here
AP_GPS_SIRF::init(s, nav_setting, DataFlash); // let the superclass do anything it might need here
}
// Private Methods //////////////////////////////////////////////////////////////

View File

@ -34,7 +34,7 @@ public:
AP_GPS_406() : AP_GPS_SIRF() {}
// Methods
virtual void init(AP_HAL::UARTDriver *s, enum GPS_Engine_Setting nav_setting);
virtual void init(AP_HAL::UARTDriver *s, enum GPS_Engine_Setting nav_setting, DataFlash_Class *DataFlash);
private:
void _change_to_sirf_protocol(void);

View File

@ -25,10 +25,11 @@ AP_GPS_Auto::AP_GPS_Auto(GPS **gps) :
// Do nothing at init time - it may be too early to try detecting the GPS
//
void
AP_GPS_Auto::init(AP_HAL::UARTDriver *s, enum GPS_Engine_Setting nav_setting)
AP_GPS_Auto::init(AP_HAL::UARTDriver *s, enum GPS_Engine_Setting nav_setting, DataFlash_Class *DataFlash)
{
_port = s;
_nav_setting = nav_setting;
_DataFlash = DataFlash;
}
@ -66,7 +67,7 @@ AP_GPS_Auto::read(void)
if (NULL != (gps = _detect())) {
// configure the detected GPS
gps->init(_port, _nav_setting);
gps->init(_port, _nav_setting, _DataFlash);
hal.console->println_P(PSTR("OK"));
*_gps = gps;
return true;
@ -126,7 +127,7 @@ AP_GPS_Auto::_detect(void)
}
if (new_gps != NULL) {
new_gps->init(_port);
new_gps->init(_port, _nav_setting, _DataFlash);
}
return new_gps;

View File

@ -24,7 +24,7 @@ public:
AP_GPS_Auto(GPS **gps);
/// Dummy init routine, does nothing
virtual void init(AP_HAL::UARTDriver *s, enum GPS_Engine_Setting nav_setting);
virtual void init(AP_HAL::UARTDriver *s, enum GPS_Engine_Setting nav_setting, DataFlash_Class *DataFlash);
/// Detect and initialise the attached GPS unit. Updates the
/// pointer passed into the constructor when a GPS is detected.

View File

@ -27,9 +27,11 @@
extern const AP_HAL::HAL& hal;
// Public Methods //////////////////////////////////////////////////////////////
void AP_GPS_HIL::init(AP_HAL::UARTDriver *s, enum GPS_Engine_Setting nav_setting)
void AP_GPS_HIL::init(AP_HAL::UARTDriver *s, enum GPS_Engine_Setting nav_setting, DataFlash_Class *DataFlash)
{
_port = s;
_nav_setting = nav_setting;
_DataFlash = DataFlash;
}
bool AP_GPS_HIL::read(void)
@ -57,7 +59,6 @@ void AP_GPS_HIL::setHIL(Fix_Status fix_status,
altitude_cm = _altitude*1.0e2f;
ground_speed_cm = _ground_speed*1.0e2f;
ground_course_cd = _ground_course*1.0e2f;
speed_3d_cm = _speed_3d*1.0e2f;
num_sats = _num_sats;
fix = fix_status,
hdop = 200;

View File

@ -32,7 +32,7 @@ public:
_updated(false)
{}
virtual void init(AP_HAL::UARTDriver *s, enum GPS_Engine_Setting nav_setting);
virtual void init(AP_HAL::UARTDriver *s, enum GPS_Engine_Setting nav_setting, DataFlash_Class *DataFlash);
virtual bool read(void);
/**

View File

@ -29,7 +29,7 @@
// Public Methods //////////////////////////////////////////////////////////////
void
AP_GPS_MTK::init(AP_HAL::UARTDriver *s, enum GPS_Engine_Setting nav_setting)
AP_GPS_MTK::init(AP_HAL::UARTDriver *s, enum GPS_Engine_Setting nav_setting, DataFlash_Class *DataFlash)
{
_port = s;
_port->flush();

View File

@ -37,7 +37,7 @@ public:
_payload_counter(0)
{}
virtual void init(AP_HAL::UARTDriver *s, enum GPS_Engine_Setting nav_setting);
virtual void init(AP_HAL::UARTDriver *s, enum GPS_Engine_Setting nav_setting, DataFlash_Class *DataFlash);
virtual bool read(void);
static bool _detect(uint8_t );

View File

@ -31,7 +31,7 @@ extern const AP_HAL::HAL& hal;
// Public Methods //////////////////////////////////////////////////////////////
void
AP_GPS_MTK19::init(AP_HAL::UARTDriver *s, enum GPS_Engine_Setting nav_setting)
AP_GPS_MTK19::init(AP_HAL::UARTDriver *s, enum GPS_Engine_Setting nav_setting, DataFlash_Class *DataFlash)
{
_port = s;
_port->flush();

View File

@ -41,7 +41,7 @@ public:
_fix_counter(0)
{}
virtual void init(AP_HAL::UARTDriver *s, enum GPS_Engine_Setting nav_setting);
virtual void init(AP_HAL::UARTDriver *s, enum GPS_Engine_Setting nav_setting, DataFlash_Class *DataFlash);
virtual bool read(void);
static bool _detect(uint8_t );

View File

@ -97,7 +97,7 @@ const char AP_GPS_NMEA::_gpvtg_string[] PROGMEM = "GPVTG";
#define DIGIT_TO_VAL(_x) (_x - '0')
// Public Methods //////////////////////////////////////////////////////////////
void AP_GPS_NMEA::init(AP_HAL::UARTDriver *s, enum GPS_Engine_Setting nav_setting)
void AP_GPS_NMEA::init(AP_HAL::UARTDriver *s, enum GPS_Engine_Setting nav_setting, DataFlash_Class *DataFlash)
{
_port = s;

View File

@ -70,7 +70,7 @@ public:
/// Perform a (re)initialisation of the GPS; sends the
/// protocol configuration messages.
///
virtual void init(AP_HAL::UARTDriver *s, enum GPS_Engine_Setting nav_setting);
virtual void init(AP_HAL::UARTDriver *s, enum GPS_Engine_Setting nav_setting, DataFlash_Class *DataFlash);
/// Checks the serial receive buffer for characters,
/// attempts to parse NMEA data and updates internal state

View File

@ -11,7 +11,7 @@ class AP_GPS_None : public GPS
public:
AP_GPS_None() : GPS() {}
virtual void init(AP_HAL::UARTDriver *s, enum GPS_Engine_Setting nav_setting) {
virtual void init(AP_HAL::UARTDriver *s, enum GPS_Engine_Setting nav_setting, DataFlash_Class *DataFlash) {
_port = s;
};
virtual bool read(void) {

View File

@ -35,7 +35,7 @@ static const uint8_t init_messages[] PROGMEM = {
// Public Methods //////////////////////////////////////////////////////////////
void
AP_GPS_SIRF::init(AP_HAL::UARTDriver *s, enum GPS_Engine_Setting nav_setting)
AP_GPS_SIRF::init(AP_HAL::UARTDriver *s, enum GPS_Engine_Setting nav_setting, DataFlash_Class *DataFlash)
{
_port = s;
_port->flush();

View File

@ -38,7 +38,7 @@ public:
_msg_id(0)
{}
virtual void init(AP_HAL::UARTDriver *s, enum GPS_Engine_Setting nav_setting);
virtual void init(AP_HAL::UARTDriver *s, enum GPS_Engine_Setting nav_setting, DataFlash_Class *DataFlash);
virtual bool read();
static bool _detect(uint8_t data);

View File

@ -27,16 +27,14 @@ GPS::GPS(void) :
altitude_cm(0),
ground_speed_cm(0),
ground_course_cd(0),
speed_3d_cm(0),
hdop(0),
num_sats(0),
new_data(false),
fix(FIX_NONE),
valid_read(false),
last_fix_time(0),
_have_raw_velocity(false),
_last_gps_time(0),
_secondary_gps(false),
_last_gps_time(0),
_idleTimer(0),
_status(GPS::NO_FIX),
_last_ground_speed_cm(0),
@ -63,7 +61,7 @@ GPS::update(void)
Debug("gps read timeout %lu %lu", (unsigned long)tnow, (unsigned long)_idleTimer);
_status = NO_GPS;
init(_port, _nav_setting);
init(_port, _nav_setting, _DataFlash);
// reset the idle timer
_idleTimer = tnow;
}
@ -77,7 +75,6 @@ GPS::update(void)
_status = NO_FIX;
}
valid_read = true;
new_data = true;
// reset the idle timer

View File

@ -7,11 +7,12 @@
#define __GPS_H__
#include <AP_HAL.h>
#include <inttypes.h>
#include <AP_Progmem.h>
#include <AP_Math.h>
class DataFlash_Class;
/// @class GPS
/// @brief Abstract base class for GPS receiver drivers.
class GPS
@ -79,7 +80,7 @@ public:
///
/// Must be implemented by the GPS driver.
///
virtual void init(AP_HAL::UARTDriver *s, enum GPS_Engine_Setting engine_setting = GPS_ENGINE_NONE) = 0;
virtual void init(AP_HAL::UARTDriver *s, enum GPS_Engine_Setting engine_setting, DataFlash_Class *dataflash) = 0;
// Properties
uint32_t time_week_ms; ///< GPS time (milliseconds from start of GPS week)
@ -89,20 +90,15 @@ public:
int32_t altitude_cm; ///< altitude in cm
uint32_t ground_speed_cm; ///< ground speed in cm/sec
int32_t ground_course_cd; ///< ground course in 100ths of a degree
int32_t speed_3d_cm; ///< 3D speed in cm/sec (not always available)
int16_t hdop; ///< horizontal dilution of precision in cm
uint8_t num_sats; ///< Number of visible satelites
/// Set to true when new data arrives. A client may set this
/// to false in order to avoid processing data they have
/// already seen.
bool new_data;
bool new_data:1;
Fix_Status fix; ///< 0 if we have no fix, 2 for 2D fix, 3 for 3D fix
bool valid_read; ///< true if we have seen data from the GPS (use ::status instead)
// Debug support
bool print_errors; ///< deprecated
// HIL support
virtual void setHIL(Fix_Status fix_status,
@ -198,7 +194,10 @@ protected:
int32_t _vel_down;
// does this GPS support raw velocity numbers?
bool _have_raw_velocity;
bool _have_raw_velocity:1;
// this is a secondary GPS, disable notify updates
bool _secondary_gps:1;
// detected baudrate
uint16_t _baudrate;
@ -206,15 +205,13 @@ protected:
// the time we got the last GPS timestamp
uint32_t _last_gps_time;
// this is a secondary GPS, disable notify updates
bool _secondary_gps;
// return time in seconds since GPS epoch given time components
void _make_gps_time(uint32_t bcd_date, uint32_t bcd_milliseconds);
DataFlash_Class *_DataFlash;
private:
/// Last time that the GPS driver got a good packet from the GPS
///
uint32_t _idleTimer;

View File

@ -27,7 +27,7 @@ void setup()
hal.uartB->begin(57600, 128, 16);
gps.print_errors = true;
gps.init(hal.uartB, GPS::GPS_ENGINE_AIRBORNE_4G); // GPS Initialization
gps.init(hal.uartB, GPS::GPS_ENGINE_AIRBORNE_4G, NULL); // GPS Initialization
hal.scheduler->delay(1000);
}
void loop()

View File

@ -35,7 +35,7 @@ void setup()
hal.console->println("GPS AUTO library test");
gps = &GPS;
gps->init(hal.uartB, GPS::GPS_ENGINE_AIRBORNE_4G);
gps->init(hal.uartB, GPS::GPS_ENGINE_AIRBORNE_4G, NULL);
// initialise the leds
board_led.init();

View File

@ -30,7 +30,7 @@ void setup()
gps.print_errors = true;
hal.console->println("GPS MTK library test");
gps.init(hal.uartB, GPS::GPS_ENGINE_AIRBORNE_4G); // GPS Initialization
gps.init(hal.uartB, GPS::GPS_ENGINE_AIRBORNE_4G, NULL); // GPS Initialization
}
void loop()

View File

@ -51,7 +51,7 @@ void setup()
for (uint8_t i = 0; i < sizeof(sirf_to_nmea); i++)
hal.uartB->write(sirf_to_nmea[i]);
gps->init(hal.uartB, GPS::GPS_ENGINE_AIRBORNE_4G);
gps->init(hal.uartB, GPS::GPS_ENGINE_AIRBORNE_4G, NULL);
}
void loop()

View File

@ -30,7 +30,7 @@ void setup()
gps.print_errors = true;
hal.console->println("GPS UBLOX library test");
gps.init(hal.uartB, GPS::GPS_ENGINE_AIRBORNE_4G); // GPS Initialization
gps.init(hal.uartB, GPS::GPS_ENGINE_AIRBORNE_4G, NULL); // GPS Initialization
}
void loop()