ardupilot/libraries/AP_GPS/AP_GPS_Auto.h
DrZiplok@gmail.com 8da4a29d58 Add support for the DIYD MTK v1.6 firmware
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
2010-12-24 06:35:09 +00:00

51 lines
1.1 KiB
C++

// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: t -*-
//
// Auto-detecting pseudo-GPS driver
//
#ifndef AP_GPS_Auto_h
#define AP_GPS_Auto_h
#include <GPS.h>
#include <FastSerial.h>
class AP_GPS_Auto : public GPS
{
public:
/// Constructor
///
/// @note The stream is expected to be set up and configured for the
/// correct bitrate before ::init is called.
///
/// @param port Stream connected to the GPS module.
/// @param ptr Pointer to a GPS * that will be fixed up by ::init
/// when the GPS type has been detected.
///
AP_GPS_Auto(FastSerial *port, GPS **gps);
/// Dummy init routine, does nothing
virtual void init(void);
/// Detect and initialise the attached GPS unit. Updates the
/// pointer passed into the constructor when a GPS is detected.
///
virtual bool read(void);
private:
/// Serial port connected to the GPS.
FastSerial *_FSport;
/// global GPS driver pointer, updated by auto-detection
///
GPS **_gps;
/// low-level auto-detect routine
///
GPS *_detect(void);
/// fetch a character from the port
///
int _getc(void);
};
#endif