ardupilot/libraries/AP_GPS/AP_GPS_406.h
DrZiplok@gmail.com 96a80f1c66 Cleanup.
Teach AP_GPS about FastSerial (in the few places it needs to know) and about Stream everywhere else.

Do some minor code cleanup.

Tested with Mega and uBlox.  Some issues (e.g. reporting 0 satelites) remain.



git-svn-id: https://arducopter.googlecode.com/svn/trunk@404 f9c3cf11-9bcb-44bc-f272-b75c42450872
2010-09-06 09:20:44 +00:00

30 lines
511 B
C++

// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: t -*-
#ifndef AP_GPS_406_h
#define AP_GPS_406_h
#include <GPS.h>
#define MAXPAYLOAD 100
class AP_GPS_406 : public GPS
{
public:
// Methods
AP_GPS_406(Stream *port);
void init();
void update();
private:
// Internal variables
uint8_t step;
uint8_t payload_counter;
static uint8_t buffer[MAXPAYLOAD];
void parse_gps();
void change_to_sirf_protocol(void);
void configure_gps(void);
};
#endif