2010-09-06 17:16:50 -03:00
|
|
|
|
// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: t -*-
|
2010-09-07 01:20:34 -03:00
|
|
|
|
//
|
|
|
|
|
// EM406 GPS driver for ArduPilot and ArduPilotMega.
|
|
|
|
|
// Code by Michael Smith, Jason Short, Jordi Mu<4D>oz and Jose Julio. DIYDrones.com
|
|
|
|
|
//
|
|
|
|
|
// This library is free software; you can redistribute it and / or
|
|
|
|
|
// modify it under the terms of the GNU Lesser General Public
|
|
|
|
|
// License as published by the Free Software Foundation; either
|
|
|
|
|
// version 2.1 of the License, or (at your option) any later version.
|
|
|
|
|
//
|
2010-09-06 17:16:50 -03:00
|
|
|
|
|
2012-09-27 02:18:44 -03:00
|
|
|
|
#ifndef __AP_GPS_406_H__
|
|
|
|
|
#define __AP_GPS_406_H__
|
|
|
|
|
|
|
|
|
|
#include <AP_HAL.h>
|
2010-09-06 17:16:50 -03:00
|
|
|
|
|
2010-09-07 01:20:34 -03:00
|
|
|
|
#include "AP_GPS_SIRF.h"
|
2010-09-06 17:16:50 -03:00
|
|
|
|
|
2012-08-17 03:19:44 -03:00
|
|
|
|
#define GPS_406_BITRATE 57600
|
2010-09-07 01:20:34 -03:00
|
|
|
|
|
|
|
|
|
class AP_GPS_406 : public AP_GPS_SIRF
|
2010-09-06 17:16:50 -03:00
|
|
|
|
{
|
|
|
|
|
public:
|
|
|
|
|
// Methods
|
2012-09-27 02:18:44 -03:00
|
|
|
|
AP_GPS_406(AP_HAL::UARTDriver *port);
|
2012-08-17 03:19:44 -03:00
|
|
|
|
virtual void init(enum GPS_Engine_Setting nav_setting = GPS_ENGINE_NONE);
|
2010-09-06 17:16:50 -03:00
|
|
|
|
|
|
|
|
|
private:
|
2012-08-17 03:19:44 -03:00
|
|
|
|
void _change_to_sirf_protocol(void);
|
|
|
|
|
void _configure_gps(void);
|
2010-09-06 17:16:50 -03:00
|
|
|
|
};
|
|
|
|
|
|
2012-09-27 02:18:44 -03:00
|
|
|
|
#endif // __AP_HAL_GPS_406_H__
|
2010-09-06 17:16:50 -03:00
|
|
|
|
|