2010-09-07 01:20:34 -03:00
|
|
|
// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: t -*-
|
|
|
|
//
|
|
|
|
// SiRF Binary GPS driver for ArduPilot and ArduPilotMega.
|
|
|
|
// Code by Michael Smith.
|
|
|
|
//
|
|
|
|
// 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.
|
|
|
|
//
|
|
|
|
|
|
|
|
#include "AP_GPS_SIRF.h"
|
2010-12-24 02:35:09 -04:00
|
|
|
#include <stdint.h>
|
2010-09-07 01:20:34 -03:00
|
|
|
|
|
|
|
// Initialisation messages
|
|
|
|
//
|
|
|
|
// Turn off all messages except for 0x29.
|
|
|
|
//
|
|
|
|
// XXX the bytes show up on the wire, but at least my test unit (EM-411) seems to ignore them.
|
|
|
|
//
|
2012-08-21 23:19:51 -03:00
|
|
|
static uint8_t init_messages[] = {
|
2011-10-28 15:52:50 -03:00
|
|
|
0xa0, 0xa2, 0x00, 0x08, 0xa6, 0x02, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0xa8, 0xb0, 0xb3,
|
|
|
|
0xa0, 0xa2, 0x00, 0x08, 0xa6, 0x00, 0x29, 0x01, 0x00, 0x00, 0x00, 0x00, 0x00, 0xd0, 0xb0, 0xb3
|
2010-09-07 01:20:34 -03:00
|
|
|
};
|
|
|
|
|
|
|
|
// Constructors ////////////////////////////////////////////////////////////////
|
|
|
|
AP_GPS_SIRF::AP_GPS_SIRF(Stream *s) : GPS(s)
|
|
|
|
{
|
|
|
|
}
|
|
|
|
|
|
|
|
// Public Methods //////////////////////////////////////////////////////////////
|
2011-10-28 15:52:50 -03:00
|
|
|
void
|
2012-06-10 03:34:53 -03:00
|
|
|
AP_GPS_SIRF::init(enum GPS_Engine_Setting nav_setting)
|
2011-10-28 15:52:50 -03:00
|
|
|
{
|
|
|
|
_port->flush();
|
2010-10-17 03:06:04 -03:00
|
|
|
|
2011-10-28 15:52:50 -03:00
|
|
|
// For modules that default to something other than SiRF binary,
|
|
|
|
// the module-specific subclass should take care of switching to binary mode
|
|
|
|
// before calling us.
|
2010-09-07 01:20:34 -03:00
|
|
|
|
2011-10-28 15:52:50 -03:00
|
|
|
// send SiRF binary setup messages
|
|
|
|
_port->write(init_messages, sizeof(init_messages));
|
|
|
|
idleTimeout = 1200;
|
2010-09-07 01:20:34 -03:00
|
|
|
}
|
|
|
|
|
|
|
|
// Process bytes available from the stream
|
|
|
|
//
|
|
|
|
// The stream is assumed to contain only messages we recognise. If it
|
|
|
|
// contains other messages, and those messages contain the preamble
|
|
|
|
// bytes, it is possible for this code to fail to synchronise to the
|
|
|
|
// stream immediately. Without buffering the entire message and
|
|
|
|
// re-processing it from the top, this is unavoidable. The parser
|
|
|
|
// attempts to avoid this when possible.
|
|
|
|
//
|
2010-12-24 02:35:09 -04:00
|
|
|
bool
|
|
|
|
AP_GPS_SIRF::read(void)
|
2010-09-07 01:20:34 -03:00
|
|
|
{
|
2012-08-21 23:19:51 -03:00
|
|
|
uint8_t data;
|
|
|
|
int16_t numc;
|
|
|
|
bool parsed = false;
|
2011-10-28 15:52:50 -03:00
|
|
|
|
|
|
|
numc = _port->available();
|
|
|
|
while(numc--) {
|
|
|
|
|
|
|
|
// read the next byte
|
|
|
|
data = _port->read();
|
|
|
|
|
|
|
|
switch(_step) {
|
|
|
|
|
2012-08-21 23:19:51 -03:00
|
|
|
// Message preamble detection
|
|
|
|
//
|
|
|
|
// If we fail to match any of the expected bytes, we reset
|
|
|
|
// the state machine and re-consider the failed byte as
|
|
|
|
// the first byte of the preamble. This improves our
|
|
|
|
// chances of recovering from a mismatch and makes it less
|
|
|
|
// likely that we will be fooled by the preamble appearing
|
|
|
|
// as data in some other message.
|
|
|
|
//
|
2011-10-28 15:52:50 -03:00
|
|
|
case 1:
|
|
|
|
if (PREAMBLE2 == data) {
|
|
|
|
_step++;
|
|
|
|
break;
|
|
|
|
}
|
|
|
|
_step = 0;
|
2012-08-21 23:19:51 -03:00
|
|
|
// FALLTHROUGH
|
2011-10-28 15:52:50 -03:00
|
|
|
case 0:
|
|
|
|
if(PREAMBLE1 == data)
|
|
|
|
_step++;
|
|
|
|
break;
|
|
|
|
|
2012-08-21 23:19:51 -03:00
|
|
|
// Message length
|
|
|
|
//
|
|
|
|
// We always collect the length so that we can avoid being
|
|
|
|
// fooled by preamble bytes in messages.
|
|
|
|
//
|
2011-10-28 15:52:50 -03:00
|
|
|
case 2:
|
|
|
|
_step++;
|
|
|
|
_payload_length = (uint16_t)data << 8;
|
|
|
|
break;
|
|
|
|
case 3:
|
|
|
|
_step++;
|
|
|
|
_payload_length |= data;
|
|
|
|
_payload_counter = 0;
|
|
|
|
_checksum = 0;
|
|
|
|
break;
|
|
|
|
|
2012-08-21 23:19:51 -03:00
|
|
|
// Message header processing
|
|
|
|
//
|
|
|
|
// We sniff the message ID to determine whether we are going
|
|
|
|
// to gather the message bytes or just discard them.
|
|
|
|
//
|
2011-10-28 15:52:50 -03:00
|
|
|
case 4:
|
|
|
|
_step++;
|
|
|
|
_accumulate(data);
|
|
|
|
_payload_length--;
|
|
|
|
_gather = false;
|
|
|
|
switch(data) {
|
|
|
|
case MSG_GEONAV:
|
|
|
|
if (_payload_length == sizeof(sirf_geonav)) {
|
|
|
|
_gather = true;
|
|
|
|
_msg_id = data;
|
|
|
|
}
|
|
|
|
break;
|
|
|
|
}
|
|
|
|
break;
|
|
|
|
|
2012-08-21 23:19:51 -03:00
|
|
|
// Receive message data
|
|
|
|
//
|
|
|
|
// Note that we are effectively guaranteed by the protocol
|
|
|
|
// that the checksum and postamble cannot be mistaken for
|
|
|
|
// the preamble, so if we are discarding bytes in this
|
|
|
|
// message when the payload is done we return directly
|
|
|
|
// to the preamble detector rather than bothering with
|
|
|
|
// the checksum logic.
|
|
|
|
//
|
2011-10-28 15:52:50 -03:00
|
|
|
case 5:
|
2012-08-21 23:19:51 -03:00
|
|
|
if (_gather) { // gather data if requested
|
2011-10-28 15:52:50 -03:00
|
|
|
_accumulate(data);
|
|
|
|
_buffer.bytes[_payload_counter] = data;
|
|
|
|
if (++_payload_counter == _payload_length)
|
|
|
|
_step++;
|
|
|
|
} else {
|
|
|
|
if (++_payload_counter == _payload_length)
|
|
|
|
_step = 0;
|
|
|
|
}
|
|
|
|
break;
|
|
|
|
|
2012-08-21 23:19:51 -03:00
|
|
|
// Checksum and message processing
|
|
|
|
//
|
2011-10-28 15:52:50 -03:00
|
|
|
case 6:
|
|
|
|
_step++;
|
|
|
|
if ((_checksum >> 8) != data) {
|
|
|
|
_error("GPS_SIRF: checksum error\n");
|
|
|
|
_step = 0;
|
|
|
|
}
|
|
|
|
break;
|
|
|
|
case 7:
|
|
|
|
_step = 0;
|
|
|
|
if ((_checksum & 0xff) != data) {
|
|
|
|
_error("GPS_SIRF: checksum error\n");
|
|
|
|
break;
|
|
|
|
}
|
|
|
|
if (_gather) {
|
2012-08-21 23:19:51 -03:00
|
|
|
parsed = _parse_gps(); // Parse the new GPS packet
|
2011-10-28 15:52:50 -03:00
|
|
|
}
|
|
|
|
}
|
|
|
|
}
|
|
|
|
return(parsed);
|
2010-09-07 01:20:34 -03:00
|
|
|
}
|
|
|
|
|
2010-12-24 02:35:09 -04:00
|
|
|
bool
|
2010-09-07 01:20:34 -03:00
|
|
|
AP_GPS_SIRF::_parse_gps(void)
|
|
|
|
{
|
2011-10-28 15:52:50 -03:00
|
|
|
switch(_msg_id) {
|
|
|
|
case MSG_GEONAV:
|
2012-08-21 23:19:51 -03:00
|
|
|
time = _swapl(&_buffer.nav.time);
|
2011-10-28 15:52:50 -03:00
|
|
|
//fix = (0 == _buffer.nav.fix_invalid) && (FIX_3D == (_buffer.nav.fix_type & FIX_MASK));
|
2012-08-21 23:19:51 -03:00
|
|
|
fix = (0 == _buffer.nav.fix_invalid);
|
|
|
|
latitude = _swapl(&_buffer.nav.latitude);
|
|
|
|
longitude = _swapl(&_buffer.nav.longitude);
|
|
|
|
altitude = _swapl(&_buffer.nav.altitude_msl);
|
|
|
|
ground_speed = _swapi(&_buffer.nav.ground_speed);
|
2011-10-28 15:52:50 -03:00
|
|
|
// at low speeds, ground course wanders wildly; suppress changes if we are not moving
|
|
|
|
if (ground_speed > 50)
|
2012-08-21 23:19:51 -03:00
|
|
|
ground_course = _swapi(&_buffer.nav.ground_course);
|
|
|
|
num_sats = _buffer.nav.satellites;
|
2011-10-28 15:52:50 -03:00
|
|
|
|
|
|
|
return true;
|
|
|
|
}
|
|
|
|
return false;
|
2010-09-07 01:20:34 -03:00
|
|
|
}
|
|
|
|
|
|
|
|
void
|
|
|
|
AP_GPS_SIRF::_accumulate(uint8_t val)
|
|
|
|
{
|
2011-10-28 15:52:50 -03:00
|
|
|
_checksum = (_checksum + val) & 0x7fff;
|
2010-09-07 01:20:34 -03:00
|
|
|
}
|
2012-09-17 01:43:07 -03:00
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
/*
|
|
|
|
detect a SIRF GPS
|
|
|
|
*/
|
|
|
|
bool
|
|
|
|
AP_GPS_SIRF::_detect(uint8_t data)
|
|
|
|
{
|
2012-09-24 18:10:07 -03:00
|
|
|
static uint16_t checksum;
|
|
|
|
static uint8_t step, payload_length, payload_counter;
|
2012-09-17 01:43:07 -03:00
|
|
|
|
|
|
|
switch (step) {
|
|
|
|
case 1:
|
|
|
|
if (PREAMBLE2 == data) {
|
|
|
|
step++;
|
|
|
|
break;
|
|
|
|
}
|
|
|
|
step = 0;
|
|
|
|
case 0:
|
|
|
|
payload_length = payload_counter = checksum = 0;
|
|
|
|
if (PREAMBLE1 == data)
|
|
|
|
step++;
|
|
|
|
break;
|
|
|
|
case 2:
|
|
|
|
step++;
|
|
|
|
if (data != 0) {
|
|
|
|
// only look for short messages
|
|
|
|
step = 0;
|
|
|
|
}
|
|
|
|
break;
|
|
|
|
case 3:
|
|
|
|
step++;
|
|
|
|
payload_length = data;
|
|
|
|
break;
|
|
|
|
case 4:
|
|
|
|
checksum = (checksum + data) & 0x7fff;
|
|
|
|
if (++payload_counter == payload_length)
|
|
|
|
step++;
|
|
|
|
break;
|
|
|
|
case 5:
|
|
|
|
step++;
|
|
|
|
if ((checksum >> 8) != data) {
|
|
|
|
step = 0;
|
|
|
|
}
|
|
|
|
break;
|
|
|
|
case 6:
|
|
|
|
step = 0;
|
|
|
|
if ((checksum & 0xff) == data) {
|
|
|
|
return true;
|
|
|
|
}
|
|
|
|
}
|
|
|
|
return false;
|
|
|
|
}
|