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/RTCM3_Parser.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*/14/*15RTCMv3 parser, used to support moving baseline RTK mode between two16GPS modules17*/1819#include <string.h>20#include <AP_Math/AP_Math.h>21#include "RTCM3_Parser.h"2223// reset state24void RTCM3_Parser::reset(void)25{26pkt_len = 0;27pkt_bytes = 0;28found_len = 0;29}3031// clear previous packet32void RTCM3_Parser::clear_packet(void)33{34if (found_len == 0) {35return;36}37// clear previous packet38if (pkt_bytes > found_len) {39memmove(&pkt[0], &pkt[found_len], pkt_bytes-found_len);40pkt_bytes -= found_len;41} else {42pkt_bytes = 0;43}44found_len = 0;45pkt_len = 0;46}4748// return length of found packet49uint16_t RTCM3_Parser::get_len(const uint8_t *&bytes) const50{51if (found_len > 0) {52bytes = &pkt[0];53}54return found_len;55}5657// return ID of found packet58uint16_t RTCM3_Parser::get_id(void) const59{60if (found_len == 0) {61return 0;62}63return (pkt[3]<<8 | pkt[4]) >> 4;64}6566// look for preamble to try to resync67void RTCM3_Parser::resync(void)68{69const uint8_t *p = (const uint8_t *)memchr(&pkt[1], RTCMv3_PREAMBLE, pkt_bytes-1);70if (p != nullptr) {71const uint16_t idx = p - &pkt[0];72memmove(&pkt[0], p, pkt_bytes - idx);73pkt_bytes -= idx;74if (pkt_bytes >= 3) {75pkt_len = (pkt[1]<<8 | pkt[2]) & 0x3ff;76} else {77pkt_len = 0;78}79} else {80reset();81}82}8384// parse packet85bool RTCM3_Parser::parse(void)86{87const uint8_t *parity = &pkt[pkt_len+3];88uint32_t crc1 = (parity[0] << 16) | (parity[1] << 8) | parity[2];89uint32_t crc2 = crc_crc24(pkt, pkt_len+3);90if (crc1 != crc2) {91resync();92return false;93}9495// we got a good packet96found_len = pkt_len+6;97return true;98}99100// read in one byte, return true if a full packet is available101bool RTCM3_Parser::read(uint8_t byte)102{103clear_packet();104105if (pkt_bytes > 0 && pkt[0] != RTCMv3_PREAMBLE) {106resync();107}108109if (pkt_bytes == 0 && byte != RTCMv3_PREAMBLE) {110// discard111return false;112}113114if (pkt_bytes >= sizeof(pkt)) {115// too long, resync116resync();117}118119pkt[pkt_bytes++] = byte;120121if (pkt_len == 0 && pkt_bytes >= 3) {122pkt_len = (pkt[1]<<8 | pkt[2]) & 0x3ff;123if (pkt_len == 0) {124resync();125}126}127128if (pkt_len != 0 && pkt_bytes >= pkt_len + 6) {129// got header, packet body and parity130return parse();131}132133// need more bytes134return false;135}136137#ifdef RTCM_MAIN_TEST138/*139parsing test, taking a raw file captured from UART to u-blox F9140*/141#include <sys/types.h>142#include <sys/stat.h>143#include <fcntl.h>144#include <stdlib.h>145#include <unistd.h>146#include <stdio.h>147148int main(int argc, const char *argv[])149{150const char *fname = argv[1];151int fd = ::open(fname, O_RDONLY);152if (fd == -1) {153perror(fname);154::exit(1);155}156RTCM3_Parser parser {};157uint8_t b;158while (::read(fd, &b, 1) == 1) {159if (parser.read(b)) {160const uint8_t *bytes;161printf("packet len %u ID %u\n", parser.get_len(bytes), parser.get_id());162}163}164return 0;165}166#endif167168169