2013-05-29 20:52:21 -03:00
|
|
|
// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
|
2013-08-29 02:34:34 -03:00
|
|
|
/*
|
|
|
|
This program is free software: you can redistribute it and/or modify
|
|
|
|
it under the terms of the GNU General Public License as published by
|
|
|
|
the Free Software Foundation, either version 3 of the License, or
|
|
|
|
(at your option) any later version.
|
|
|
|
|
|
|
|
This program is distributed in the hope that it will be useful,
|
|
|
|
but WITHOUT ANY WARRANTY; without even the implied warranty of
|
|
|
|
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
|
|
|
|
GNU General Public License for more details.
|
|
|
|
|
|
|
|
You should have received a copy of the GNU General Public License
|
|
|
|
along with this program. If not, see <http://www.gnu.org/licenses/>.
|
|
|
|
*/
|
|
|
|
|
2010-09-07 01:20:34 -03:00
|
|
|
//
|
|
|
|
// SiRF Binary GPS driver for ArduPilot and ArduPilotMega.
|
|
|
|
// Code by Michael Smith.
|
|
|
|
//
|
2016-02-17 21:25:23 -04:00
|
|
|
#pragma once
|
2010-09-07 01:20:34 -03:00
|
|
|
|
2015-08-11 03:28:43 -03:00
|
|
|
#include <AP_HAL/AP_HAL.h>
|
|
|
|
#include <AP_Common/AP_Common.h>
|
|
|
|
#include "AP_GPS.h"
|
2010-09-07 01:20:34 -03:00
|
|
|
|
2014-09-30 23:41:56 -03:00
|
|
|
#define SIRF_SET_BINARY "$PSRF100,0,38400,8,1,0*3C\r\n"
|
2010-10-17 03:06:04 -03:00
|
|
|
|
2014-03-28 16:52:27 -03:00
|
|
|
class AP_GPS_SIRF : public AP_GPS_Backend {
|
2010-09-07 01:20:34 -03:00
|
|
|
public:
|
2014-03-28 16:52:27 -03:00
|
|
|
AP_GPS_SIRF(AP_GPS &_gps, AP_GPS::GPS_State &_state, AP_HAL::UARTDriver *_port);
|
2013-02-19 20:32:15 -04:00
|
|
|
|
2014-03-28 00:50:44 -03:00
|
|
|
bool read();
|
|
|
|
|
2014-03-28 16:52:27 -03:00
|
|
|
static bool _detect(struct SIRF_detect_state &state, uint8_t data);
|
2010-09-07 01:20:34 -03:00
|
|
|
|
|
|
|
private:
|
2013-05-09 07:04:36 -03:00
|
|
|
struct PACKED sirf_geonav {
|
2012-08-17 03:19:44 -03:00
|
|
|
uint16_t fix_invalid;
|
|
|
|
uint16_t fix_type;
|
|
|
|
uint16_t week;
|
|
|
|
uint32_t time;
|
|
|
|
uint16_t year;
|
|
|
|
uint8_t month;
|
|
|
|
uint8_t day;
|
|
|
|
uint8_t hour;
|
|
|
|
uint8_t minute;
|
|
|
|
uint16_t second;
|
|
|
|
uint32_t satellites_used;
|
|
|
|
int32_t latitude;
|
|
|
|
int32_t longitude;
|
|
|
|
int32_t altitude_ellipsoid;
|
|
|
|
int32_t altitude_msl;
|
|
|
|
int8_t map_datum;
|
|
|
|
int16_t ground_speed;
|
|
|
|
int16_t ground_course;
|
|
|
|
int16_t res1;
|
|
|
|
int16_t climb_rate;
|
|
|
|
uint16_t heading_rate;
|
|
|
|
uint32_t horizontal_position_error;
|
|
|
|
uint32_t vertical_position_error;
|
|
|
|
uint32_t time_error;
|
|
|
|
int16_t horizontal_velocity_error;
|
|
|
|
int32_t clock_bias;
|
|
|
|
uint32_t clock_bias_error;
|
|
|
|
int32_t clock_drift;
|
|
|
|
uint32_t clock_drift_error;
|
|
|
|
uint32_t distance;
|
|
|
|
uint16_t distance_error;
|
|
|
|
uint16_t heading_error;
|
|
|
|
uint8_t satellites;
|
|
|
|
uint8_t hdop;
|
|
|
|
uint8_t mode_info;
|
2011-10-28 15:52:50 -03:00
|
|
|
};
|
|
|
|
enum sirf_protocol_bytes {
|
|
|
|
PREAMBLE1 = 0xa0,
|
|
|
|
PREAMBLE2 = 0xa2,
|
|
|
|
POSTAMBLE1 = 0xb0,
|
|
|
|
POSTAMBLE2 = 0xb3,
|
|
|
|
MSG_GEONAV = 0x29
|
|
|
|
};
|
|
|
|
enum sirf_fix_type {
|
|
|
|
FIX_3D = 0x6,
|
|
|
|
FIX_MASK = 0x7
|
|
|
|
};
|
2010-09-07 01:20:34 -03:00
|
|
|
|
|
|
|
|
2011-10-28 15:52:50 -03:00
|
|
|
// State machine state
|
2012-08-17 03:19:44 -03:00
|
|
|
uint8_t _step;
|
|
|
|
uint16_t _checksum;
|
|
|
|
bool _gather;
|
|
|
|
uint16_t _payload_length;
|
|
|
|
uint16_t _payload_counter;
|
|
|
|
uint8_t _msg_id;
|
2010-09-07 01:20:34 -03:00
|
|
|
|
2011-10-28 15:52:50 -03:00
|
|
|
// Message buffer
|
|
|
|
union {
|
2012-08-17 03:19:44 -03:00
|
|
|
sirf_geonav nav;
|
|
|
|
uint8_t bytes[];
|
2011-10-28 15:52:50 -03:00
|
|
|
} _buffer;
|
2010-09-07 01:20:34 -03:00
|
|
|
|
2012-08-17 03:19:44 -03:00
|
|
|
bool _parse_gps(void);
|
|
|
|
void _accumulate(uint8_t val);
|
2014-03-31 06:48:22 -03:00
|
|
|
|
|
|
|
static const uint8_t _initialisation_blob[];
|
2010-09-07 01:20:34 -03:00
|
|
|
};
|