mirror of
https://github.com/sunnypilot/sunnypilot.git
synced 2026-03-02 23:43:59 +08:00
* cleanup include path
* continue
* format includes
* fix testraw.cc
* remove include path from SConstruct
* regroup
* rebase master
* almost done
* apply review
* rename FileReader.xx to filereader.xx
* rename Unlogger.x->unlogger.x
* rename FrameReader.xx -> framereader.xx
* apply reviews
* ui.h
* continue
* fix framebuffer.cc build error:mv util.h up
* full path to msm_media_info
* fix qcom2 camerad
Co-authored-by: Comma Device <device@comma.ai>
old-commit-hash: 7222d0f20d
53 lines
1.6 KiB
C++
53 lines
1.6 KiB
C++
#pragma once
|
|
|
|
#include <cstdint>
|
|
#include <memory>
|
|
#include <string>
|
|
#include <unordered_map>
|
|
|
|
#include "cereal/messaging/messaging.h"
|
|
#include "selfdrive/locationd/generated/gps.h"
|
|
#include "selfdrive/locationd/generated/ubx.h"
|
|
|
|
// protocol constants
|
|
namespace ublox {
|
|
const uint8_t PREAMBLE1 = 0xb5;
|
|
const uint8_t PREAMBLE2 = 0x62;
|
|
|
|
const int UBLOX_HEADER_SIZE = 6;
|
|
const int UBLOX_CHECKSUM_SIZE = 2;
|
|
const int UBLOX_MAX_MSG_SIZE = 65536;
|
|
|
|
// Boardd still uses these:
|
|
const uint8_t CLASS_NAV = 0x01;
|
|
const uint8_t CLASS_RXM = 0x02;
|
|
const uint8_t CLASS_MON = 0x0A;
|
|
}
|
|
|
|
class UbloxMsgParser {
|
|
public:
|
|
bool add_data(const uint8_t *incoming_data, uint32_t incoming_data_len, size_t &bytes_consumed);
|
|
inline void reset() {bytes_in_parse_buf = 0;}
|
|
inline int needed_bytes();
|
|
inline std::string data() {return std::string((const char*)msg_parse_buf, bytes_in_parse_buf);}
|
|
|
|
std::pair<std::string, kj::Array<capnp::word>> gen_msg();
|
|
kj::Array<capnp::word> gen_nav_pvt(ubx_t::nav_pvt_t *msg);
|
|
kj::Array<capnp::word> gen_rxm_sfrbx(ubx_t::rxm_sfrbx_t *msg);
|
|
kj::Array<capnp::word> gen_rxm_rawx(ubx_t::rxm_rawx_t *msg);
|
|
kj::Array<capnp::word> gen_mon_hw(ubx_t::mon_hw_t *msg);
|
|
kj::Array<capnp::word> gen_mon_hw2(ubx_t::mon_hw2_t *msg);
|
|
|
|
private:
|
|
inline bool valid_cheksum();
|
|
inline bool valid();
|
|
inline bool valid_so_far();
|
|
|
|
std::unordered_map<int, std::unordered_map<int, std::string>> gps_subframes;
|
|
|
|
size_t bytes_in_parse_buf = 0;
|
|
uint8_t msg_parse_buf[ublox::UBLOX_HEADER_SIZE + ublox::UBLOX_MAX_MSG_SIZE];
|
|
|
|
};
|
|
|