Real-time collaboration for Jupyter Notebooks, Linux Terminals, LaTeX, VS Code, R IDE, and more,
all in one place. Commercial Alternative to JupyterHub.
Real-time collaboration for Jupyter Notebooks, Linux Terminals, LaTeX, VS Code, R IDE, and more,
all in one place. Commercial Alternative to JupyterHub.
Path: blob/master/libraries/AP_GPS/AP_GPS_SIRF.cpp
Views: 1798
/*1This program is free software: you can redistribute it and/or modify2it under the terms of the GNU General Public License as published by3the Free Software Foundation, either version 3 of the License, or4(at your option) any later version.56This program is distributed in the hope that it will be useful,7but WITHOUT ANY WARRANTY; without even the implied warranty of8MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the9GNU General Public License for more details.1011You should have received a copy of the GNU General Public License12along with this program. If not, see <http://www.gnu.org/licenses/>.13*/1415//16// SiRF Binary GPS driver for ArduPilot and ArduPilotMega.17// Code by Michael Smith.18//1920#include "AP_GPS_config.h"2122#if AP_GPS_SIRF_ENABLED2324#include "AP_GPS_SIRF.h"25#include <AP_HAL/utility/sparse-endian.h>26#include <stdint.h>2728// Initialisation messages29//30// Turn off all messages except for 0x29.31//32// XXX the bytes show up on the wire, but at least my test unit (EM-411) seems to ignore them.33//34const uint8_t AP_GPS_SIRF::_initialisation_blob[] = {350xa0, 0xa2, 0x00, 0x08, 0xa6, 0x02, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0xa8, 0xb0, 0xb3,360xa0, 0xa2, 0x00, 0x08, 0xa6, 0x00, 0x29, 0x01, 0x00, 0x00, 0x00, 0x00, 0x00, 0xd0, 0xb0, 0xb337};3839AP_GPS_SIRF::AP_GPS_SIRF(AP_GPS &_gps, AP_GPS::Params &_params, AP_GPS::GPS_State &_state, AP_HAL::UARTDriver *_port) :40AP_GPS_Backend(_gps, _params, _state, _port)41{42gps.send_blob_start(state.instance, (const char *)_initialisation_blob, sizeof(_initialisation_blob));43}444546// Process bytes available from the stream47//48// The stream is assumed to contain only messages we recognise. If it49// contains other messages, and those messages contain the preamble50// bytes, it is possible for this code to fail to synchronise to the51// stream immediately. Without buffering the entire message and52// re-processing it from the top, this is unavoidable. The parser53// attempts to avoid this when possible.54//55bool56AP_GPS_SIRF::read(void)57{58uint8_t data;59int16_t numc;60bool parsed = false;6162numc = port->available();63while(numc--) {6465// read the next byte66data = port->read();6768switch(_step) {6970// Message preamble detection71//72// If we fail to match any of the expected bytes, we reset73// the state machine and re-consider the failed byte as74// the first byte of the preamble. This improves our75// chances of recovering from a mismatch and makes it less76// likely that we will be fooled by the preamble appearing77// as data in some other message.78//79case 1:80if (PREAMBLE2 == data) {81_step++;82break;83}84_step = 0;85FALLTHROUGH;86case 0:87if(PREAMBLE1 == data)88_step++;89break;9091// Message length92//93// We always collect the length so that we can avoid being94// fooled by preamble bytes in messages.95//96case 2:97_step++;98_payload_length = (uint16_t)data << 8;99break;100case 3:101_step++;102_payload_length |= data;103_payload_counter = 0;104_checksum = 0;105break;106107// Message header processing108//109// We sniff the message ID to determine whether we are going110// to gather the message bytes or just discard them.111//112case 4:113_step++;114_accumulate(data);115_payload_length--;116_gather = false;117switch(data) {118case MSG_GEONAV:119if (_payload_length == sizeof(sirf_geonav)) {120_gather = true;121_msg_id = data;122}123break;124}125break;126127// Receive message data128//129// Note that we are effectively guaranteed by the protocol130// that the checksum and postamble cannot be mistaken for131// the preamble, so if we are discarding bytes in this132// message when the payload is done we return directly133// to the preamble detector rather than bothering with134// the checksum logic.135//136case 5:137if (_gather) { // gather data if requested138_accumulate(data);139_buffer[_payload_counter] = data;140if (++_payload_counter == _payload_length)141_step++;142} else {143if (++_payload_counter == _payload_length)144_step = 0;145}146break;147148// Checksum and message processing149//150case 6:151_step++;152if ((_checksum >> 8) != data) {153_step = 0;154}155break;156case 7:157_step = 0;158if ((_checksum & 0xff) != data) {159break;160}161if (_gather) {162parsed = _parse_gps(); // Parse the new GPS packet163}164}165}166return(parsed);167}168169bool170AP_GPS_SIRF::_parse_gps(void)171{172switch(_msg_id) {173case MSG_GEONAV:174//time = _swapl(&_buffer.nav.time);175// parse fix type176if (_buffer.nav.fix_invalid) {177state.status = AP_GPS::NO_FIX;178}else if ((_buffer.nav.fix_type & FIX_MASK) == FIX_3D) {179state.status = AP_GPS::GPS_OK_FIX_3D;180}else{181state.status = AP_GPS::GPS_OK_FIX_2D;182}183state.location.lat = int32_t(be32toh(_buffer.nav.latitude));184state.location.lng = int32_t(be32toh(_buffer.nav.longitude));185const int32_t alt_amsl = int32_t(be32toh(_buffer.nav.altitude_msl));186const int32_t alt_ellipsoid = int32_t(be32toh(_buffer.nav.altitude_ellipsoid));187state.undulation = (alt_amsl - alt_ellipsoid)*0.01;188state.have_undulation = true;189set_alt_amsl_cm(state, alt_amsl);190state.ground_speed = int32_t(be32toh(_buffer.nav.ground_speed))*0.01f;191state.ground_course = wrap_360(int16_t(be16toh(_buffer.nav.ground_course)*0.01f));192state.num_sats = _buffer.nav.satellites;193fill_3d_velocity();194return true;195}196return false;197}198199void200AP_GPS_SIRF::_accumulate(uint8_t val)201{202_checksum = (_checksum + val) & 0x7fff;203}204205206207/*208detect a SIRF GPS209*/210bool AP_GPS_SIRF::_detect(struct SIRF_detect_state &state, uint8_t data)211{212switch (state.step) {213case 1:214if (PREAMBLE2 == data) {215state.step++;216break;217}218state.step = 0;219FALLTHROUGH;220case 0:221state.payload_length = state.payload_counter = state.checksum = 0;222if (PREAMBLE1 == data)223state.step++;224break;225case 2:226state.step++;227if (data != 0) {228// only look for short messages229state.step = 0;230}231break;232case 3:233state.step++;234state.payload_length = data;235break;236case 4:237state.checksum = (state.checksum + data) & 0x7fff;238if (++state.payload_counter == state.payload_length) {239state.step++;240}241break;242case 5:243state.step++;244if ((state.checksum >> 8) != data) {245state.step = 0;246}247break;248case 6:249state.step = 0;250if ((state.checksum & 0xff) == data) {251return true;252}253}254return false;255}256257#endif // AP_GPS_SIRF_ENABLED258259260