mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-04 06:58:27 -04:00
52a0a03d56
- disable NMEA autodetection; false positives are still a risk - trim down the console output to a minimum; we still need something to help users diagnose potential problems, but the old output was much too verbose - rather than block forever, only do one autodetect pass for each ::read call. That's still too long (five seconds or so) but better than blocking forever. - don't block forever if no GPS is attached. git-svn-id: https://arducopter.googlecode.com/svn/trunk@1480 f9c3cf11-9bcb-44bc-f272-b75c42450872
52 lines
1.2 KiB
C++
52 lines
1.2 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 <FastSerial.h>
|
|
#include <GPS.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 *s, 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:
|
|
/// Copy of the port, known at construction time to be a real FastSerial port.
|
|
FastSerial *_fs;
|
|
|
|
/// global GPS driver pointer, updated by auto-detection
|
|
///
|
|
GPS **_gps;
|
|
|
|
/// low-level auto-detect routine
|
|
///
|
|
GPS *_detect(void);
|
|
|
|
static const prog_char _mtk_set_binary[];
|
|
static const prog_char _ublox_set_binary[];
|
|
static const prog_char _sirf_set_binary[];
|
|
|
|
};
|
|
#endif
|