diff --git a/Makefile b/Makefile index 4b7613d..3342ae8 100644 --- a/Makefile +++ b/Makefile @@ -173,7 +173,7 @@ $(BUILD_DIR)/.make-uid: | $(BUILD_DIR) .PHONY: cmake cmake: $(BUILD_DIR)/.make-cmake -deps = $(sort $(wildcard CMakeList.txt Makefile fpsdk_doc/* Doxyfile \ +deps = $(sort $(wildcard CMakeList.txt Makefile fpsdk_doc/* \ fpsdk_common/* fpsdk_common/*/* fpsdk_common/*/*/* fpsdk_common/*/*/*/* \ fpsdk_ros1/* fpsdk_ros1/*/* fpsdk_ros1/*/*/* fpsdk_ros1/*/*/*/* \ fpsdk_ros2/* fpsdk_ros2/*/* fpsdk_ros2/*/*/* fpsdk_ros2/*/*/*/* \ @@ -222,14 +222,15 @@ endif .PHONY: doc doc: $(BUILD_DIR)/.make-doc -$(BUILD_DIR)/.make-doc: $(BUILD_DIR)/.make-cmake +$(BUILD_DIR)/.make-doc: $(BUILD_DIR)/.make-cmake fpsdk_doc/Doxyfile @echo "$(HLW)***** Doc ($(BUILD_TYPE)) *****$(HLO)" $(V)( \ - cat Doxyfile; \ + cat fpsdk_doc/Doxyfile; \ echo "PROJECT_NUMBER = $$(cat $(BUILD_DIR)/FP_VERSION_STRING || echo 'unknown revision')"; \ echo "OUTPUT_DIRECTORY = $(BUILD_DIR)"; \ ) | $(DOXYGEN) - $(V)$(TOUCH) $@ + @echo "now run: xdg-open $(BUILD_DIR)/doc/index.html" # ---------------------------------------------------------------------------------------------------------------------- diff --git a/docker/scripts/install_aptbase.sh b/docker/scripts/install_aptbase.sh index acb76e1..4888e9b 100755 --- a/docker/scripts/install_aptbase.sh +++ b/docker/scripts/install_aptbase.sh @@ -20,6 +20,7 @@ packages=$(awk -v filt=${FPSDK_IMAGE%-*} '$1 ~ filt { print $2 }' <:fpsdk_ros1> ) +file(GLOB PARSERTOOL_CPP_FILES parsertool/*.cpp) +add_executable(parsertool ${PARSERTOOL_CPP_FILES} ${COMMON_CPP_FILES}) +target_link_libraries(parsertool + fpsdk_common +) + file(GLOB TIMECONV_CPP_FILES timeconv/*.cpp) add_executable(timeconv ${TIMECONV_CPP_FILES} ${COMMON_CPP_FILES}) target_link_libraries(timeconv @@ -91,7 +99,7 @@ set(PROJECT_LIBRARY_DIR ${CMAKE_INSTALL_FULL_LIBDIR}) set(PROJECT_INCLUDE_DIR ${CMAKE_INSTALL_FULL_INCLUDEDIR}/${PROJECT_NAME}) set(PROJECT_DATA_DIR ${CMAKE_INSTALL_FULL_DATAROOTDIR}/${PROJECT_NAME}) -install(TARGETS fpltool timeconv yaml2shell +install(TARGETS fpltool parsertool timeconv yaml2shell EXPORT ${PROJECT_NAME}-targets LIBRARY DESTINATION ${PROJECT_LIBRARY_DIR} RUNTIME DESTINATION ${PROJECT_RUNTIME_DIR} diff --git a/fpsdk_apps/README.md b/fpsdk_apps/README.md index af8aba6..7604c34 100644 --- a/fpsdk_apps/README.md +++ b/fpsdk_apps/README.md @@ -5,7 +5,7 @@ This contains various apps (tools, utilities). See below for details. --- ## Dependencies -- [Fixposition SDK dependencies](../README.md#dependencies) +- [Fixposition SDK dependencies](../fpsdk_docs/README.md#dependencies) - [fpsdk_common](../fpsdk_common/README.md) - [fpsdk_ros1](../fpsdk_common/README.md) -- optional, but recommended, and required for some functionality diff --git a/fpsdk_apps/common/common.cpp b/fpsdk_apps/common/common.cpp new file mode 100644 index 0000000..f721e13 --- /dev/null +++ b/fpsdk_apps/common/common.cpp @@ -0,0 +1,84 @@ +/** + * \verbatim + * ___ ___ + * \ \ / / + * \ \/ / Copyright (c) Fixposition AG (www.fixposition.com) and contributors + * / /\ \ License: see the LICENSE file + * /__/ \__\ + * \endverbatim + * + * @file + * @brief Fixposition SDK: common app utils + */ + +/* LIBC/STL */ +#include +#include +#include + +/* EXTERNAL */ + +/* Fixposition SDK */ +#include +#include + +/* PACKAGE */ +#include "common.hpp" + +namespace fpsdk { +namespace apps { +namespace common { +/* ****************************************************************************************************************** */ + +using namespace fpsdk::common::string; +using namespace fpsdk::common::parser; + +// --------------------------------------------------------------------------------------------------------------------- + +void PrintMessageHeader() +{ + // Keep in sync with PrintMessage() + std::printf("------- Seq# Offset Size Protocol Message Info\n"); +} + +// --------------------------------------------------------------------------------------------------------------------- + +void PrintMessageData(const ParserMsg& msg, const std::size_t offs, const bool hexdump) +{ + msg.MakeInfo(); + std::printf("message %06" PRIuMAX " %8" PRIuMAX " %5" PRIuMAX " %-8s %-30s %s\n", msg.seq_, offs, msg.data_.size(), + ProtocolStr(msg.proto_), msg.name_.c_str(), msg.info_.empty() ? "-" : msg.info_.c_str()); + if (hexdump) { + for (auto& line : HexDump(msg.data_)) { + std::printf("%s\n", line.c_str()); + } + } +} + +// --------------------------------------------------------------------------------------------------------------------- + +void PrintParserStats(const ParserStats& stats) +{ + auto& s = stats; + const double p_n = (s.n_msgs_ > 0 ? 100.0 / (double)s.n_msgs_ : 0.0); + const double p_s = (s.s_msgs_ > 0 ? 100.0 / (double)s.s_msgs_ : 0.0); + std::printf("Stats: Messages Bytes\n"); + const char* fmt = "%-8s %10" PRIu64 " (%5.1f%%) %10" PRIu64 " (%5.1f%%)\n"; + // clang-format off + std::printf(fmt, "Total", s.n_msgs_, (double)s.n_msgs_ * p_n, s.s_msgs_, (double)s.s_msgs_ * p_s); + std::printf(fmt, ProtocolStr(Protocol::FP_A), s.n_fpa_, (double)s.n_fpa_ * p_n, s.s_fpa_, (double)s.s_fpa_ * p_s); + std::printf(fmt, ProtocolStr(Protocol::FP_B), s.n_fpb_, (double)s.n_fpb_ * p_n, s.s_fpb_, (double)s.s_fpb_ * p_s); + std::printf(fmt, ProtocolStr(Protocol::NMEA), s.n_nmea_, (double)s.n_nmea_ * p_n, s.s_nmea_, (double)s.s_nmea_ * p_s); + std::printf(fmt, ProtocolStr(Protocol::UBX), s.n_ubx_, (double)s.n_ubx_ * p_n, s.s_ubx_, (double)s.s_ubx_ * p_s); + std::printf(fmt, ProtocolStr(Protocol::RTCM3), s.n_rtcm3_, (double)s.n_rtcm3_ * p_n, s.s_rtcm3_, (double)s.s_rtcm3_ * p_s); + std::printf(fmt, ProtocolStr(Protocol::NOV_B), s.n_novb_, (double)s.n_novb_ * p_n, s.s_novb_, (double)s.s_novb_ * p_s); + std::printf(fmt, ProtocolStr(Protocol::UNI_B), s.n_unib_, (double)s.n_unib_ * p_n, s.s_novb_, (double)s.s_unib_ * p_s); + std::printf(fmt, ProtocolStr(Protocol::SPARTN), s.n_spartn_, (double)s.n_spartn_ * p_n, s.s_spartn_, (double)s.s_spartn_ * p_s); + std::printf(fmt, ProtocolStr(Protocol::OTHER), s.n_other_, (double)s.n_other_ * p_n, s.s_other_, (double)s.s_other_ * p_s); + // clang-format on +} + +/* ****************************************************************************************************************** */ +} // namespace common +} // namespace apps +} // namespace fpsdk diff --git a/fpsdk_apps/common/common.hpp b/fpsdk_apps/common/common.hpp new file mode 100644 index 0000000..374c9fe --- /dev/null +++ b/fpsdk_apps/common/common.hpp @@ -0,0 +1,62 @@ +/** + * \verbatim + * ___ ___ + * \ \ / / + * \ \/ / Copyright (c) Fixposition AG (www.fixposition.com) and contributors + * / /\ \ License: see the LICENSE file + * /__/ \__\ + * \endverbatim + * + * @file + * @brief Fixposition SDK: common app utils + */ +#ifndef __FPSDK_APPS_PCOMMOM_HPP__ +#define __FPSDK_APPS_PCOMMOM_HPP__ + +/* LIBC/STL */ +#include +#include +#include + +/* EXTERNAL */ + +/* Fixposition SDK */ +#include +#include + +/* PACKAGE */ + +namespace fpsdk { +namespace apps { +/** + * @brief common apps utils + */ +namespace common { +/* ****************************************************************************************************************** */ + +/** + * @brief Print header for PrintMessageData() to stdout + */ +void PrintMessageHeader(); + +/** + * @brief Print message summary to stdout + * + * @param[in] msg The message + * @param[in] offs Offset [bytes] of message in data (stream, file) + * @param[in] hexdump Print also hexdump + */ +void PrintMessageData(const ::fpsdk::common::parser::ParserMsg& msg, const std::size_t offs, const bool hexdump); + +/** + * @brief Print parser stats to stdout + * + * @param[in] stats The stats + */ +void PrintParserStats(const ::fpsdk::common::parser::ParserStats& stats); + +/* ****************************************************************************************************************** */ +} // namespace common +} // namespace apps +} // namespace fpsdk +#endif // __FPSDK_APPS_PCOMMOM_HPP__ diff --git a/fpsdk_apps/doc/doc.hpp b/fpsdk_apps/doc/doc.hpp index 86be5f8..a189040 100644 --- a/fpsdk_apps/doc/doc.hpp +++ b/fpsdk_apps/doc/doc.hpp @@ -32,6 +32,7 @@ namespace apps { @section FPSDK_APPS_APPS Apps - @subpage FPSDK_APPS_FPLTOOL + - @subpage FPSDK_APPS_PARSERTOOL - @subpage FPSDK_APPS_TIMECONV - @subpage FPSDK_APPS_YAML2SHELL diff --git a/fpsdk_apps/fpltool/fpltool_rosbag.cpp b/fpsdk_apps/fpltool/fpltool_rosbag.cpp index 0b84fc5..21fea6a 100644 --- a/fpsdk_apps/fpltool/fpltool_rosbag.cpp +++ b/fpsdk_apps/fpltool/fpltool_rosbag.cpp @@ -24,7 +24,7 @@ #include #ifdef FP_USE_ROS1 # include -# include +# include #endif /* PACKAGE */ @@ -90,7 +90,7 @@ bool DoRosbag(const FplToolOptions& opts) // Prepare message for stream messages fpsdk_ros1::ParserMsg stream_msg_ros; - stream_msg_ros.protocol = fpsdk_ros1::ParserMsg::PROTOCOL_UNSPECIFIED; + stream_msg_ros.protocol = fpsdk::ros1::msgs::ParserMsg::PROTOCOL_UNSPECIFIED; stream_msg_ros.seq = 0; // Handle SIGINT (C-c) to abort nicely diff --git a/fpsdk_apps/parsertool/parsertool.cpp b/fpsdk_apps/parsertool/parsertool.cpp new file mode 100644 index 0000000..9ddc748 --- /dev/null +++ b/fpsdk_apps/parsertool/parsertool.cpp @@ -0,0 +1,289 @@ +/** + * \verbatim + * ___ ___ + * \ \ / / + * \ \/ / Copyright (c) Fixposition AG (www.fixposition.com) and contributors + * / /\ \ License: see the LICENSE file + * /__/ \__\ + * \endverbatim + * + * @file + * @brief Fixposition SDK: parsertool main + */ + +/* LIBC/STL */ +#include +#include +#include +#include +#include + +/* EXTERNAL */ +#include + +/* Fixposition SDK */ +#include +#include +#include +#include +#include + +/* PACKAGE */ +#include "../common/common.hpp" + +namespace fpsdk { +namespace apps { +namespace parsertool { +/* ****************************************************************************************************************** */ + +using namespace fpsdk::common::app; +using namespace fpsdk::common::parser; +using namespace fpsdk::common::string; +using namespace fpsdk::common::time; +using namespace fpsdk::apps::common; + +// --------------------------------------------------------------------------------------------------------------------- + +// Program options +class ParserToolOptions : public ProgramOptions +{ + public: + ParserToolOptions() // clang-format off + : ProgramOptions("parsertool", { { 'x', false }, { 's', false } }) {}; // clang-format on + + // clang-format off + bool hexdump_ = false; //!< Do hexdump of messages + bool split_ = false; //!< Split individual messages and save to files + std::vector inputs_; //!< Input file(s) + // clang-format on + + void PrintHelp() final + { + // clang-format off + std::fputs( + "\n" + "This parses input data from stdin or file(s) into individual messages (frames) and\n" + "dumps some information about them to stdout.\n" + "\n" + "Usage:\n" + "\n" + " parsertool [flags] [ ...]\n" + "\n" + "Where:\n" + "\n" ,stdout); + std::fputs(COMMON_FLAGS_HELP, stdout); + std::fputs( + " -x -- Print hexdump of each message\n" + " -s -- Save each (!) message into a separate (!) file in the current directory\n" + " -- File or device to read data from (instead of stdin)\n" + "\n" + "Examples:\n" + "\n" + " Parse messages from a file:\n" + "\n" + " parsertool fpsdk_common/test/data/mixed.bin\n" + "\n" + " Read data from stdin:\n" + "\n" + " cat fpsdk_common/test/data/mixed.bin | parsertool\n" + " parsertool < fpsdk_common/test/data/mixed.bin\n" + "\n" + " Read from a TCP/IP socket server:\n" + "\n" + " nc 10.0.1.1 21000 | parsertool\n" + "\n" + " Read from a serial port (such as a USB to serial converter):\n" + "\n" + " stty -F /dev/ttyUSB0 115200 raw -echo; parsertool /dev/ttyUSB0\n" + "\n", stdout); + // clang-format on + } + + bool HandleOption(const Option& option, const std::string& /*argument*/) final + { + bool ok = true; + switch (option.flag) { + case 'x': + hexdump_ = true; + break; + case 's': + split_ = true; + break; + default: + ok = false; + break; + } + return ok; + } + + bool CheckOptions(const std::vector& args) final + { + bool ok = true; + + // Any further positional arguments are inputs + inputs_ = args; + + for (std::size_t ix = 0; ix < inputs_.size(); ix++) { + DEBUG("inputs_[%" PRIuMAX "] = '%s'", ix, inputs_[ix].c_str()); + } + DEBUG("hexdump = %s", hexdump_ ? "true" : "false"); + DEBUG("split = %s", split_ ? "true" : "false"); + + return ok; + } +}; + +/* ****************************************************************************************************************** */ + +class ParserTool +{ + public: + ParserTool(const ParserToolOptions& opts) : opts_{ opts }, offs_{ 0 } + { + } + + bool Run() + { + // Print header + PrintMessageHeader(); + + // Process data from stdin + if (opts_.inputs_.empty()) { + INFO("Reading from stdin"); + std::ios_base::sync_with_stdio(false); + ProcessInput(std::cin); + } + + // Process all input files + bool ok = true; + for (const auto& input_file : opts_.inputs_) { + INFO("Reading from %s", input_file.c_str()); + std::ifstream input(input_file, std::ios::binary); + if (input.good()) { + ProcessInput(input); + } else { + WARNING("Failed reading from %s: %s", input_file.c_str(), StrError(errno).c_str()); + ok = false; + } + if (sigint_.ShouldAbort() || !ok) { + break; + } + } + + //! Print statistics + PrintParserStats(parser_.GetStats()); + + return ok; + } + + private: + // ----------------------------------------------------------------------------------------------------------------- + + ParserToolOptions opts_; //!< Program options + SigIntHelper sigint_; //!< Handle SIGINT (C-c) to abort nicely + Parser parser_; //!< Parser + std::size_t offs_; //!< Offset of message in input data + + // ----------------------------------------------------------------------------------------------------------------- + + void ProcessInput(std::istream& input) + { + // Run all data through the parser and print what it finds... + + ParserMsg msg; + const auto tenms = Duration::FromNSec(10000000); + + while (!sigint_.ShouldAbort() && input.good() && !input.eof()) { + // Read a chunk of data from the logfile + uint8_t data[MAX_ADD_SIZE]; + const int size = input.readsome((char*)data, sizeof(data)); + + // We may be at end of file + if (size <= 0) { + // End of file + if (input.peek() == EOF) { + break; + } + // More data may be available later (e.g. when reading from stdin, pipe, device) + // @todo Use select() + else { + tenms.Sleep(); // @todo necessary? + continue; + } + } + + // Add the chunk of data to the parser + if (!parser_.Add(data, size)) { + WARNING("Parser overflow"); + parser_.Reset(); + continue; + } + + // Run parser and print messages to the screen + while (parser_.Process(msg)) { + PrintMessageData(msg, offs_, opts_.hexdump_); + offs_ += msg.data_.size(); + if (opts_.split_) { + SaveMessage(msg); + } + } + } + + // There may be some remaining data in the parser + while (parser_.Flush(msg)) { + PrintMessageData(msg, offs_, opts_.hexdump_); + offs_ += msg.data_.size(); + if (opts_.split_) { + SaveMessage(msg); + } + } + } + + // ----------------------------------------------------------------------------------------------------------------- + + void SaveMessage(const ParserMsg& msg) + { + const auto output_file = Sprintf("%06" PRIuMAX "_%s.bin", msg.seq_, msg.name_.c_str()); + std::ofstream output(output_file, std::ios::binary); + output.write((const char*)msg.data_.data(), msg.data_.size()); + output.close(); + } +}; + +/* ****************************************************************************************************************** */ +} // namespace parsertool +} // namespace apps +} // namespace fpsdk + +/* ****************************************************************************************************************** */ + +int main(int argc, char** argv) +{ + using namespace fpsdk::apps::parsertool; +#ifndef NDEBUG + fpsdk::common::app::StacktraceHelper stacktrace; +#endif + bool ok = true; + + // Parse command line arguments + ParserToolOptions opts; + if (!opts.LoadFromArgv(argc, argv)) { + ok = false; + } + + if (ok) { + ParserTool app(opts); + ok = app.Run(); + } + + // Are we happy? + if (ok) { + INFO("Done"); + return EXIT_SUCCESS; + } else { + ERROR("Failed"); + return EXIT_FAILURE; + } +} + +/* ****************************************************************************************************************** */ diff --git a/fpsdk_apps/parsertool/parsertool_doc.hpp b/fpsdk_apps/parsertool/parsertool_doc.hpp new file mode 100644 index 0000000..62c294c --- /dev/null +++ b/fpsdk_apps/parsertool/parsertool_doc.hpp @@ -0,0 +1,88 @@ +/** + * \verbatim + * ___ ___ + * \ \ / / + * \ \/ / Copyright (c) Fixposition AG (www.fixposition.com) and contributors + * / /\ \ License: see the LICENSE file + * /__/ \__\ + * \endverbatim + * + * @file + * @brief Fixposition SDK: parsertool documentation + */ + +#ifndef __FPSDK_APPS_PARSERTOOL_PARSERTOOL_DOC_HPP__ +#define __FPSDK_APPS_PARSERTOOL_PARSERTOOL_DOC_HPP__ + +namespace fpsdk { +namespace apps { +/** + * @brief parsertool + */ +namespace parsertool { +// clang-format off +/* ****************************************************************************************************************** */ + +/*! + @page FPSDK_APPS_PARSERTOOL Parser tool + + @section FPSDK_APPS_PARSERTOOL_OVERVIEW Overview + + This demonstrates the use of the @ref FPSDK_COMMON_PARSER + + For example: + + @verbatim + $ parsertool fpsdk_common/test/data/mixed.bin + @endverbatim + + Outputs: + + @verbatim + Reading from fpsdk_common/test/data/mixed.bin + ------- Seq# Size Protocol Message + message 000001 109 FP_A FP_A-ODOMETRY + message 000002 70 NMEA NMEA-GN-RMC + message 000003 104 NOV_B NOV_B-BESTPOS + message 000004 42 OTHER OTHER + message 000005 28 RTCM3 RTCM3-TYPE1107 + message 000006 48 SPARTN SPARTN-OCB-GLO + message 000007 24 UBX UBX-TIM-TP + message 000008 20 OTHER OTHER + message 000009 104 FP_A FP_A-TF + message 000010 82 NMEA NMEA-GN-GGA + message 000011 144 NOV_B NOV_B-BESTXYZ + message 000012 295 RTCM3 RTCM3-TYPE1077 + message 000013 259 SPARTN SPARTN-OCB-GPS + message 000014 68 UBX UBX-MON-HW + message 000015 40 OTHER OTHER + message 000016 56 NOV_B NOV_B-RAWIMUSX + message 000017 52 RTCM3 RTCM3-TYPE1033 + message 000018 28 SPARTN SPARTN-GAD-GAD + message 000019 256 OTHER OTHER + message 000020 24 OTHER OTHER + message 000021 36 UBX UBX-MON-HW2 + message 000022 192 SPARTN SPARTN-HPAC-GLO + message 000023 72 UBX UBX-NAV-COV + message 000024 256 OTHER OTHER + message 000025 256 OTHER OTHER + message 000026 68 OTHER OTHER + Stats: Messages Bytes + Total 26 (100.0%) 2733 (100.0%) + FP_A 2 ( 7.7%) 213 ( 7.8%) + FP_B 0 ( 0.0%) 0 ( 0.0%) + NMEA 2 ( 7.7%) 152 ( 5.6%) + UBX 4 ( 15.4%) 200 ( 7.3%) + RTCM3 3 ( 11.5%) 375 ( 13.7%) + NOV_B 3 ( 11.5%) 304 ( 11.1%) + SPARTN 4 ( 15.4%) 527 ( 19.3%) + OTHER 8 ( 30.8%) 962 ( 35.2%) + @endverbatim +*/ + +/* ****************************************************************************************************************** */ +// clang-format on +} // namespace parsertool +} // namespace apps +} // namespace fpsdk +#endif // __FPSDK_APPS_PARSERTOOL_PARSERTOOL_DOC_HPP__ diff --git a/fpsdk_apps/yaml2shell/yaml2shell.cpp b/fpsdk_apps/yaml2shell/yaml2shell.cpp index b010e81..bc4f349 100644 --- a/fpsdk_apps/yaml2shell/yaml2shell.cpp +++ b/fpsdk_apps/yaml2shell/yaml2shell.cpp @@ -231,7 +231,7 @@ class YamlToShell try { out_ = std::make_unique(opts_.output_, std::ios::binary); if (!out_ || out_->fail()) { - throw std::runtime_error(std::strerror(errno)); + throw std::runtime_error(StrError(errno).c_str()); } } catch (std::exception& ex) { WARNING("Open %s fail: %s", opts_.output_.c_str(), ex.what()); diff --git a/fpsdk_common/CMakeLists.txt b/fpsdk_common/CMakeLists.txt index f4cbfed..d633efd 100644 --- a/fpsdk_common/CMakeLists.txt +++ b/fpsdk_common/CMakeLists.txt @@ -67,7 +67,7 @@ include_directories(include # SHARED LIBRARY ======================================================================================================= -file(GLOB CPP_FILES src/*.cpp) +file(GLOB CPP_FILES src/*.cpp src/parser/*.cpp) add_library(${PROJECT_NAME} SHARED ${CPP_FILES}) if (FP_USE_PROJ) @@ -172,8 +172,19 @@ include(cmake/testing.cmake) add_gtest(TARGET app_test SOURCES test/app_test.cpp LINK_LIBS ${PROJECT_NAME}) add_gtest(TARGET fpl_test SOURCES test/fpl_test.cpp LINK_LIBS ${PROJECT_NAME}) add_gtest(TARGET logging_test SOURCES test/logging_test.cpp LINK_LIBS ${PROJECT_NAME}) +add_gtest(TARGET gnss_test SOURCES test/gnss_test.cpp LINK_LIBS ${PROJECT_NAME}) add_gtest(TARGET math_test SOURCES test/math_test.cpp LINK_LIBS ${PROJECT_NAME}) add_gtest(TARGET parser_test SOURCES test/parser_test.cpp LINK_LIBS ${PROJECT_NAME}) +add_gtest(TARGET parser_crc_test SOURCES test/parser_crc_test.cpp LINK_LIBS ${PROJECT_NAME}) +add_gtest(TARGET parser_fpa_test SOURCES test/parser_fpa_test.cpp LINK_LIBS ${PROJECT_NAME}) +add_gtest(TARGET parser_fpb_test SOURCES test/parser_fpb_test.cpp LINK_LIBS ${PROJECT_NAME}) +add_gtest(TARGET parser_nmea_test SOURCES test/parser_nmea_test.cpp LINK_LIBS ${PROJECT_NAME}) +add_gtest(TARGET parser_novb_test SOURCES test/parser_novb_test.cpp LINK_LIBS ${PROJECT_NAME}) +add_gtest(TARGET parser_rtcm3_test SOURCES test/parser_rtcm3_test.cpp LINK_LIBS ${PROJECT_NAME}) +add_gtest(TARGET parser_spartn_test SOURCES test/parser_spartn_test.cpp LINK_LIBS ${PROJECT_NAME}) +add_gtest(TARGET parser_types_test SOURCES test/parser_types_test.cpp LINK_LIBS ${PROJECT_NAME}) +add_gtest(TARGET parser_ubx_test SOURCES test/parser_ubx_test.cpp LINK_LIBS ${PROJECT_NAME}) +add_gtest(TARGET parser_unib_test SOURCES test/parser_unib_test.cpp LINK_LIBS ${PROJECT_NAME}) add_gtest(TARGET path_test SOURCES test/path_test.cpp LINK_LIBS ${PROJECT_NAME}) add_gtest(TARGET stream_test SOURCES test/stream_test.cpp LINK_LIBS ${PROJECT_NAME}) add_gtest(TARGET string_test SOURCES test/string_test.cpp LINK_LIBS ${PROJECT_NAME}) diff --git a/fpsdk_common/LICENSE b/fpsdk_common/LICENSE index 7b06e95..a1d9711 100644 --- a/fpsdk_common/LICENSE +++ b/fpsdk_common/LICENSE @@ -54,3 +54,27 @@ CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. + + +-------------------------------------------------------------------------------- + +Parts of fpcommon are based on NovAtel code: + +Copyright (c) 2020 NovAtel Inc. + +Permission is hereby granted, free of charge, to any person obtaining a copy +of this software and associated documentation files (the "Software"), to deal +in the Software without restriction, including without limitation the rights +to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +copies of the Software, and to permit persons to whom the Software is +furnished to do so, subject to the following conditions: + +The above copyright notice and this permission notice shall be included in all +copies or substantial portions of the Software. + +THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE diff --git a/fpsdk_common/README.md b/fpsdk_common/README.md index 0fdc3d1..0e946be 100644 --- a/fpsdk_common/README.md +++ b/fpsdk_common/README.md @@ -5,7 +5,7 @@ This library contains various common functionality. This is used for example by --- ## Dependencies -- [Fixposition SDK dependencies](../fpsdk_doc/README.md#dependencies) +- [Fixposition SDK dependencies](../fpsdk_docs/README.md#dependencies) - This does *not* need any ROS diff --git a/fpsdk_common/cmake/setup.cmake b/fpsdk_common/cmake/setup.cmake index 3de7d53..fd8b52c 100644 --- a/fpsdk_common/cmake/setup.cmake +++ b/fpsdk_common/cmake/setup.cmake @@ -34,16 +34,14 @@ if(NOT "${ROS_PACKAGE_PATH}" STREQUAL "") # - ROS1 environment loaded. Recommended. elseif(NOT "$ENV{ROS_PACKAGE_PATH}" STREQUAL "") message(STATUS "fpsdk: Using ROS1 (environment ROS_PACKAGE_PATH=$ENV{ROS_PACKAGE_PATH})") - string(REPLACE ":" ";" ROS_PACKAGE_PATH_LIST $ENV{ROS_PACKAGE_PATH}) - list(APPEND CMAKE_PREFIX_PATH ${ROS_PACKAGE_PATH_LIST}) + # Environment (catkin) should already set CMAKE_PREFIX_PATH correctly. However, we seem to need this: list(APPEND CMAKE_PREFIX_PATH /opt/ros/noetic) set(FP_USE_ROS1 ON) # - ROS2 environment loaded elseif("$ENV{ROS_VERSION}" STREQUAL "2") message(STATUS "fpsdk: Using ROS2") set(FP_USE_ROS2 ON) - # TODO: Probably this also needs some stuff added to CMAKE_PREFIX_PATH. We're not currently using any ROS2 libs - # anywhere in fpsdk_apps... + # TODO: Maybe this also needs some stuff added to CMAKE_PREFIX_PATH? else() message(STATUS "fpsdk: No ROS environment detected") endif() diff --git a/fpsdk_common/doc/parser.drawio.svg b/fpsdk_common/doc/parser.drawio.svg new file mode 100644 index 0000000..80a741c --- /dev/null +++ b/fpsdk_common/doc/parser.drawio.svg @@ -0,0 +1,218 @@ + + + + + + + +
+
+
+ fpsdk::common::parser +
+
+
+
+ + fpsdk::common::parser + +
+
+ + + + +
+
+
+ Parser +
+
+
+
+ + Parser + +
+
+ + + + + +
+
+
+ state +
+
+
+
+ + state + +
+
+ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +
+
+
+ Bytes +
+
+
+
+ + Bytes + +
+
+ + + + +
+
+
+ Add() +
+
+
+
+ + Add() + +
+
+ + + + +
+
+
+ Process() +
+
+
+
+ + Process() + +
+
+ + + + +
+
+
+ Messages +
+
+
+
+ + Messages + +
+
+ + + + +
+
+
+ decode and use messages... +
+
+
+
+ + decode and use me... + +
+
+ + + + +
+
+
+ read data from file, socket, port, ... +
+
+
+
+ + read data from fil... + +
+
+ + + + + + + + +
+
+
+ Protocol definitions and utilities +
+
+
+
+ + Protocol definitions and utilities + +
+
+ + + + +
+ + + + + Text is not SVG - cannot display + + + +
\ No newline at end of file diff --git a/fpsdk_common/include/fpsdk_common/fpl.hpp b/fpsdk_common/include/fpsdk_common/fpl.hpp index 05f94fe..438e4c9 100644 --- a/fpsdk_common/include/fpsdk_common/fpl.hpp +++ b/fpsdk_common/include/fpsdk_common/fpl.hpp @@ -309,7 +309,7 @@ struct LogStatus uint32_t log_time_posix_; //!< Approximate time std::string log_time_iso_; //!< Approximate time int8_t pos_source_; //!< Approximate sensor position source (see POS_SOURCE_... below) - int8_t pos_fix_type_; //!< Approximate sensor position fix type (see fpsdk::common::types::GnssFixType) + int8_t pos_fix_type_; //!< Approximate sensor position fix type (see fpsdk::common::gnss::GnssFixType) double pos_lat_; //!< Approximate sensor position latitude [deg] double pos_lon_; //!< Approximate sensor position longitude [deg] double pos_height_; //!< Approximate sensor position height [m] diff --git a/fpsdk_common/include/fpsdk_common/gnss.hpp b/fpsdk_common/include/fpsdk_common/gnss.hpp new file mode 100644 index 0000000..513026a --- /dev/null +++ b/fpsdk_common/include/fpsdk_common/gnss.hpp @@ -0,0 +1,366 @@ +/** + * \verbatim + * ___ ___ + * \ \ / / + * \ \/ / Copyright (c) Fixposition AG (www.fixposition.com) and contributors + * / /\ \ License: see the LICENSE file + * /__/ \__\ + * + * Based on work by flipflip (https://github.com/phkehl) + * \endverbatim + * + * @file + * @brief Fixposition SDK: GNSS types and utilities + * + * @page FPSDK_COMMON_GNSS GNSS types and utilities + * + * **API**: fpsdk_common/gnss.hpp and fpsdk::common::gnss + * + */ +#ifndef __FPSDK_COMMON_GNSS_HPP__ +#define __FPSDK_COMMON_GNSS_HPP__ + +/* LIBC/STL */ +#include + +/* EXTERNAL */ + +/* PACKAGE */ +#include "types.hpp" + +namespace fpsdk { +namespace common { +/** + * @brief GNSS types and utilities + */ +namespace gnss { +/* ****************************************************************************************************************** */ + +/** + * @brief GNSS fix types + */ +enum class GnssFixType : uint8_t +{ // clang-format off + UNKNOWN = 0, //!< Unknown fix + NOFIX = 1, //!< No fix + DRONLY = 2, //!< Dead-reckoning only fix + TIME = 3, //!< Time only fix + SPP_2D = 4, //!< 2D fix + SPP_3D = 5, //!< 3D fix + SPP_3D_DR = 6, //!< 3D + dead-reckoning fix + RTK_FLOAT = 7, //!< RTK float fix (implies 3D fix) + RTK_FIXED = 8, //!< RTK fixed fix (implies 3D fix) + RTK_FLOAT_DR = 9, //!< RTK float fix + dead-reckoning (implies RTK_FLOAT fix) + RTK_FIXED_DR = 10, //!< RTK fixed fix + dead-reckoning (implies RTK_FIXED fix) +}; // clang-format on + +/** + * @brief Stringify GNSS fix type + * + * @param[in] fix_type The fix type + * + * @returns a concise and unique string for the fix types, "?" for bad values + */ +const char* GnssFixTypeStr(const GnssFixType fix_type); + +/** + * @brief GNSS + */ +enum class Gnss : uint8_t +{ // clang-format off + UNKNOWN = 0, //!< Unknown/unspecified GNSS + GPS = 'G', //!< GPS + SBAS = 'S', //!< SBAS + GAL = 'E', //!< Galileo + BDS = 'C', //!< BeiDou + QZSS = 'J', //!< QZSS + GLO = 'R', //!< GLONASS + NAVIC = 'I', //!< NavIC (IRNSS) +}; // clang-format on + +/** + * @brief Stringify GNSS + * + * @param[in] gnss The GNSS + * + * @returns a concise and unique string for the GNSS, "?" for bad values + */ +const char* GnssStr(const Gnss gnss); + +/** + * @brief Signals + */ +enum class Signal : uint8_t +{ // clang-format off + UNKNOWN = 0, //!< Unknown/unspecified signal + BDS_B1C, //!< BeiDou B1c signal (B1 Cp and B1 Cd) + BDS_B1I, //!< BeiDou B1I signal (B1I D1 and B1I D2) + BDS_B2A, //!< BeiDou B2a signal (B2 ap and B2 ad) + BDS_B2I, //!< BeiDou B2I signal (B2I D1 and B2I D2) + GAL_E1, //!< Galileo E1 signal (E1 C and E1 B) + GAL_E5A, //!< Galileo E5a signal (E5 aI and E5 aQ) + GAL_E5B, //!< Galileo E5b signal (E5 bI and E5 bQ) + GLO_L1OF, //!< GLONASS L1 OF signal + GLO_L2OF, //!< GLONASS L2 OF signal + GPS_L1CA, //!< GPS L1 C/A signal + GPS_L2C, //!< GPS L2 C signal (L2 CL and L2 CM) + GPS_L5, //!< GPS L5 signal (L5 I and L5 Q) + QZSS_L1CA, //!< QZSS L1 C/A signal + QZSS_L1S, //!< QZSS L1 S (SAIF) signal + QZSS_L2C, //!< QZSS L2 C signal (L2 CL and L2 CM) + QZSS_L5, //!< QZSS L5 signal (L5 I and L5 Q) + SBAS_L1CA, //!< SBAS L1 C/A signal + NAVIC_L5A, //!< NavIC L5 A +}; // clang-format on + +/** + * @brief Stringify signal + * + * @param[in] signal The signal + * + * @returns a concise and unique string for the signal, "?" for bad values + */ +const char* SignalStr(const Signal signal); + +/** + * @brief Frequency bands + */ +enum class Band : uint8_t +{ + UNKNOWN = 0, //!< Unknown/unspecified band + L1, //!< L1 band (~1.5GHz) + L2, //!< L2 band (~1.2GHz) + L5, //!< L5 band (~1.1GHz) +}; + +/** + * @brief Stringify frequency band + * + * @param[in] band The frequency band + * + * @returns a concise and unique string for the frequency band, "?" for bad values + */ +const char* BandStr(const Band band); + +/** + * @brief Get frequency band for a signal + * + * @param[in] signal The signal + * + * @returns the frequency band for the signal + */ +Band SignalToBand(const Signal signal); + +/** + * @brief Satellite number (within a GNSS) + */ +using SvNr = uint8_t; + +// Number of satellites per constellation, see https://igs.org/mgex/constellations/. Satellite numbers are two digits +// satellite numbers as defined by IGS (see RINEX v3.04 section 3.5). +// clang-format off +static constexpr SvNr NUM_GPS = 32; //!< Number of GPS satellites (G01-G32, PRN) +static constexpr SvNr NUM_SBAS = 39; //!< Number of SBAS satellites (S20-S59, PRN - 100) +static constexpr SvNr NUM_GAL = 36; //!< Number of Galileo satellites (E01-E36, PRN) +static constexpr SvNr NUM_BDS = 63; //!< Number of BeiDou satellites (C01-C63, PRN) +static constexpr SvNr NUM_QZSS = 10; //!< Number of QZSS satellites (J01-J10, PRN - 192) +static constexpr SvNr NUM_GLO = 32; //!< Number of GLONASS satellites (R01-R32, slot) +static constexpr SvNr NUM_NAVIC = 14; //!< Number of NavIC satellites (I01-I14, PRN) +static constexpr SvNr FIRST_GPS = 1; //!< First GPS satellite number +static constexpr SvNr FIRST_SBAS = 20; //!< First SBAS satellite number +static constexpr SvNr FIRST_GAL = 1; //!< First Galileo satellite number +static constexpr SvNr FIRST_BDS = 1; //!< First BeiDou satellite number +static constexpr SvNr FIRST_QZSS = 1; //!< First QZSS satellite number +static constexpr SvNr FIRST_GLO = 1; //!< First GLONASS satellite number +static constexpr SvNr FIRST_NAVIC = 1; //!< First NavIC satellite number +static constexpr SvNr INAVLID_SVNR = 0; //!< Invalid satellite number (in any GNSS) +// clang-format on + +// --------------------------------------------------------------------------------------------------------------------- + +/** + * @brief Satellite ("sat"), consisting of GNSS and satellite number, suitable for indexing and sorting + */ +using Sat = uint16_t; + +/** + * @brief Get "sat" from GNSS and satellite ID + * + * @note This does not do any range checking and it's up to the user to provide a valid satellite ID for the given GNSS. + * + * @param[in] gnss GNSS + * @param[in] svnr Satellite ID + * + * @returns the "sat" + */ +static constexpr Sat GnssSvNrToSat(const Gnss gnss, const SvNr svnr) +{ + return ((Sat)types::EnumToVal(gnss) << 8) | (Sat)svnr; +} + +/** + * @brief Invalid "sat" + * + * @note This is not the only invalid combination of GNSS and satellite number! + */ +static constexpr Sat INVALID_SAT = GnssSvNrToSat(Gnss::UNKNOWN, INAVLID_SVNR); + +/** + * @brief Get GNSS from "sat" + * + * @param[in] sat The "sat" + * + * @returns the GNSS + */ +static constexpr Gnss SatToGnss(const Sat sat) +{ + return (Gnss)((sat >> 8) & 0xff); +} + +/** + * @brief Get satellite nr from "sat" + * + * @param[in] sat The "sat" + * + * @returns the satellite nr + */ +static constexpr SvNr SatToSvNr(const Sat sat) +{ + return sat & 0xff; +} + +// --------------------------------------------------------------------------------------------------------------------- + +/** + * @brief Satellite plus frequency band and signal ("satsig"), suitable for indexing and sorting + */ +using SatSig = uint32_t; + +/** + * @brief Get "satsig" from components + * + * @note This does not do any range checking and it's up to the user to provide a valid satellite ID for the given GNSS. + * + * @param[in] gnss GNSS + * @param[in] svnr Satellite ID + * @param[in] band Frequency band + * @param[in] signal Signal + * + * @returns the "satsig" + */ +static constexpr SatSig GnssSvNrBandSignalToSatSig( + const Gnss gnss, const SvNr svnr, const Band band, const Signal signal) +{ + return ((SatSig)types::EnumToVal(gnss) << 24) | ((SatSig)svnr << 16) | ((SatSig)band << 8) | (SatSig)signal; +} + +/** + * @brief Invalid "satsig"" + * + * @note This is not the only invalid combination of GNSS, satellite number, band and signal! + */ +static constexpr SatSig INVALID_SATSIG = + GnssSvNrBandSignalToSatSig(Gnss::UNKNOWN, INAVLID_SVNR, Band::UNKNOWN, Signal::UNKNOWN); + +/** + * @brief Get GNSS from "satsig" + * + * @param[in] satsig The "satsig" + * + * @returns the GNSS + */ +static constexpr Gnss SatSigToGnss(const SatSig satsig) +{ + return (Gnss)((satsig >> 24) & 0xff); +} + +/** + * @brief Get satellite nr from "satsig" + * + * @param[in] satsig The "satsig" + * + * @returns the satellite nr + */ +static constexpr SvNr SatSigToSvNr(const SatSig satsig) +{ + return (SvNr)((satsig >> 16) & 0xff); +} + +/** + * @brief Get frequency band from "satsig" + * + * @param[in] satsig The "satsig" + * + * @returns the frequency band + */ +static constexpr Band SatSigToBand(const SatSig satsig) +{ + return (Band)((satsig >> 8) & 0xff); +} + +/** + * @brief Get signal from "satsig" + * + * @param[in] satsig The "satsig" + * + * @returns the signal + */ +static constexpr Signal SatSigToSignal(const SatSig satsig) +{ + return (Signal)(satsig & 0xff); +} + +// --------------------------------------------------------------------------------------------------------------------- + +/** + * @brief Stringify satellite + * + * @param[in] sat The satellite + * + * @returns a unique string identifying the satellite + */ +const char* SatStr(const Sat sat); + +/** + * @brief Satellite from string + * + * @param[in] str The string ("G03", "R22", "C12", ...) + * + * @returns the satellite (INVALID_SAT if str was invalid) + */ +Sat StrSat(const char* str); + +/** + * @brief Convert UBX gnssId to GNSS + * + * @param[in] gnssId UBX gnssId + * + * @returns the GNSS + */ +Gnss UbxGnssIdToGnss(const uint8_t gnssId); + +/** + * @brief Convert UBX gnssId and svId to satellite + * + * @param[in] gnssId UBX gnssId + * @param[in] svId UBX svId + * + * @returns the satellite, INVALID_SAT for invalid gnssId/svId + */ +Sat UbxGnssIdSvIdToSat(const uint8_t gnssId, const uint8_t svId); + +/** + * @brief Convert UBX gnssId and sigId to signal + * + * @param[in] gnssId UBX gnssId + * @param[in] sigId UBX sigId + * + * @returns the signal + */ +Signal UbxGnssIdSigIdToSignal(const uint8_t gnssId, const uint8_t sigId); + +/* ****************************************************************************************************************** */ +} // namespace gnss +} // namespace common +} // namespace fpsdk +#endif // __FPSDK_COMMON_GNSS_HPP__ diff --git a/fpsdk_common/include/fpsdk_common/logging.hpp b/fpsdk_common/include/fpsdk_common/logging.hpp index e604836..4c1315b 100644 --- a/fpsdk_common/include/fpsdk_common/logging.hpp +++ b/fpsdk_common/include/fpsdk_common/logging.hpp @@ -156,6 +156,14 @@ namespace logging { // clang-format on ///@} +#if !defined(NDEBUG) || defined(_DOXYGEN_) // Only for non-Release builds +//! Conditional compilation for non-Release builds +# define IF_TRACE(...) __VA_ARGS__ +#else +# define IF_TRACE(...) /* nothing */ +#endif +// Note: for other levels use LoggingIsLevel() + // --------------------------------------------------------------------------------------------------------------------- /** @@ -313,7 +321,7 @@ void LoggingPrint(const LoggingLevel level, const char* fmt, ...) PRINTF_ATTR(2) * @param[in] fmt printf() style format string (for a first line to print), can be NULL to omit * @param[in] ... Arguments to the format string */ -void LoggingHexdump(const LoggingLevel level, const uint8_t* data, const uint64_t size, const char* prefix, +void LoggingHexdump(const LoggingLevel level, const uint8_t* data, const std::size_t size, const char* prefix, const char* fmt, ...) PRINTF_ATTR(5); // Helper macros diff --git a/fpsdk_common/include/fpsdk_common/parser.hpp b/fpsdk_common/include/fpsdk_common/parser.hpp index fa95245..227fe70 100644 --- a/fpsdk_common/include/fpsdk_common/parser.hpp +++ b/fpsdk_common/include/fpsdk_common/parser.hpp @@ -5,6 +5,8 @@ * \ \/ / Copyright (c) Fixposition AG (www.fixposition.com) and contributors * / /\ \ License: see the LICENSE file * /__/ \__\ + * + * Based on work by flipflip (https://github.com/phkehl) * \endverbatim * * @file @@ -14,15 +16,139 @@ * * **API**: fpsdk_common/parser.hpp and fpsdk::common::parser * + * @section FPSDK_COMMON_PARSER_INTRO Introduction + * + * This implements a message parser for various protocols (see #fpsdk::common::parser::Protocol). A + * fpsdk::common::parser::Parser object is fed with data and it emits one fpsdk::common::parser::ParserMsg after + * another. No data is discarded, any data input into the parser is also output as a message. Unknown parts of the input + * data (other protocols not recognised by this parser, incorrect or incomplete messages, spurious data, line noise, + * etc.) are output as one or multiple messages of type fpsdk::common::parser::Protocol::OTHER. + * + * Note that the Parser does not *decode* messages. It only *extracts* messages (frames) from a stream of bytes. + * The *decoding* of messages, i.e. decoding the data or fields from the message payload must be done by the + * application. However, a number of types and utility functions to facilitate this are included. + * + * The Parser code is organised into the following parts: + * + * - @subpage FPSDK_COMMON_PARSER_TYPES + * - @subpage FPSDK_COMMON_PARSER_CRC + * - @subpage FPSDK_COMMON_PARSER_FPA + * - @subpage FPSDK_COMMON_PARSER_FPB + * - @subpage FPSDK_COMMON_PARSER_NMEA + * - @subpage FPSDK_COMMON_PARSER_NOVB + * - @subpage FPSDK_COMMON_PARSER_RTCM3 + * - @subpage FPSDK_COMMON_PARSER_SPARTN + * - @subpage FPSDK_COMMON_PARSER_UBX + * - @subpage FPSDK_COMMON_PARSER_UNIB + * + * @section FPSDK_COMMON_PARSER_USAGE Usage + * + * The usage of the parser is best explained in source code: + * + * @code{cpp} + * #include + * #include + * + * #include + * #include + * + * using namespace fpsdk::common::parser; + * + * std::ifstream input("some_logfile.bin", std::ios::binary); + * Parser parser; + * ParserMsg msg; + * + * while (input.good()) { + * + * // Read a chunk of data from the logfile + * uint8_t data[MAX_ADD_SIZE]; + * const std::size_t size = input.readsome((char*)data, sizeof(data)); + * + * // No more data from file + * if (size <= 0) { + * break; + * } + * + * // Add the chunk of data to the parser + * if (!parser.Add(data, size)) { + * // We added too much data! This will not happen if we don't add more than MAX_ANY_SIZE at a time. + * WARNING(("Parser overflow!"); + * parser.Reset(); + * continue; + * } + * + * // Run parser and print message name and size to the screen + * while (parser.Process(msg)) { + * msg.MakeInfo(); // Try to populate msg.info_ + * INFO("Message %s, size %d (%s)", msg.name_.c_str(), (int)msg.data_.size(), msg.info_.c_str()); + * } + * } + * + * // There may be some remaining data in the parser. + * // If there is anytghing, we should see only type OTHER "messages" here. + * while (parser.Flush(msg)) { + * msg.MakeInfo(); + * INFO("Message %s, size %d", msg.name_.c_str(), (int)msg.data_.size(), msg.info_.c_str()); + * } + * @endcode + * + * For a more sophisticated example app see the @ref FPSDK_APPS_PARSERTOOL (fpsdk_apps/parsertool/parsertool.cpp). + * + * @section FPSDK_COMMON_PARSER_NAMING Protocol and message naming + * + * The protocols names are defined in #fpsdk::common::parser::Protocol and can be stringified using + * fpsdk::common::parser::ProtocolStr(). The names must match `/^[A-Z][A-Z0-9_]{2,5}$/. + * + * The message naming scheme consists of words separated by dashes. The first word is always the protocol name. + * Depending on the protocol one or two more words are added. All words must match `/^[A-Z][A-Z0-9]{2,9}$/`. + * + * Examples: + * + * - **FP_A**-NAME, e.g. `FP_A-ODOMETRY`, `FP_A-RAWIMU`. See fpsdk::common::parser::nmea::NmeaGetMessageName() for + * details. + * - **FP_B**-NAME, e.g. `FP_B-SYSTEMSTATUS`, `FP_B-GNSSSTATUS`. See fpsdk::common::parser::fpb::FpbGetMessageName() for + * details. + * - **NMEA**-TALKER-FORMATTER, e.g. `NMEA-GN-GGA`, `NMEA-GN-RMC`. See fpsdk::common::parser::nmea::NmeaGetMessageName() + * for details. + * - **UBX**-CLASS-MESSAGE, e.g. `UBX-NAV-PVT`, `UBX-RXM-RAWX`. See fpsdk::common::parser::ubx::UbxGetMessageName() for + * details. + * - **RTCM3**-TYPENNNN, e.g. `RTCM3-TYPE1234`. See fpsdk::common::parser::rtcm3::Rtcm3GetMessageName() for details. + * - **UNI_B**-NAME, .e.g. `UNI_B-VERSION`, `UNI_B-BESTNAV`. See fpsdk::common::parser::unib::UnibGetMessageName() for + * details. + * - **NOV_B**-NAME, .e.g. `NOV_B-BESTGNSSPOS`, `NOV_B-RAWDMI`. See fpsdk::common::parser::novb::NovbGetMessageName() + * for details. + * - **SPARTN**-TYPE-SUBTYPE, e.g. `SPARTN-OCB-GPS`. See fpsdk::common::parser::spartn::SpartnGetMessageName() for + * details. + * - **OTHER** (there are no individual messages in this "protocol") + * + * @section FPSDK_COMMON_PARSER_DESIGN Design + * + * @image html parser.drawio.svg "" + * + * The parser implementation does not use any STL containers, templates or other c++ conveniences. Instead, low-level + * c-like types are used, in order to prevent any expensive heap (re)allocation and too much copying of data. For + * example, the returned ParserMsg contains a pointer to message rather than a std::vector, and a const + * char* message name instead of a std::string. Applications can convert (copy) these easily to std::vector resp. + * std::string for further processing. Some of the utilities, such as fpsdk::common::parser::ubx::UbxMakeMessage(), do + * use STL containers for convenience. + * + * The maximum message size for each protocol is limited. For example, while the FP_B frame meta data would allow for + * messages up to 65'536 bytes, the parser discards any message larger than #fpsdk::common::parser::MAX_FP_B_SIZE. + * Messages larger than this are not practical and they do not (should not) exist. For example, it would take 5.6 + * seconds for such a message to transfer over a serial port at baudrate 115'200. + * */ #ifndef __FPSDK_COMMON_PARSER_HPP__ #define __FPSDK_COMMON_PARSER_HPP__ /* LIBC/STL */ +#include +#include /* EXTERNAL */ /* PACKAGE */ +#include "parser/types.hpp" namespace fpsdk { namespace common { @@ -32,6 +158,95 @@ namespace common { namespace parser { /* ****************************************************************************************************************** */ +/** + * @brief Message parser class + */ +class Parser +{ + public: + // + // ----- Constructor ----------------------------------------------------------------------------------------------- + + /** + * @brief Constructor, initialises parser and makes it ready to accept data and emit messages + */ + Parser(); + + // + // ----- Input data ------------------------------------------------------------------------------------------------ + + /** + * @brief Add data to parser + * + * @param[in] data Pointer to data + * @param[in] size Size of data (should be <= #MAX_ADD_SIZE) + * + * @returns true if data was added to the parser, false if there was not enough space left + */ + bool Add(const uint8_t* data, const std::size_t size); + + /** + * @brief Add data to parser + * + * @param[in] data data, can be empty (should be <= #MAX_ADD_SIZE) + * + * @returns true if data was added to the parser, false if there was not enough space left + */ + bool Add(const std::vector& data); + + /** + * @brief Reset parser + * + * Resets the parser state and discards all collected data. + */ + void Reset(); + + // + // ----- Process data (run parser) --------------------------------------------------------------------------------- + + /** + * @brief Process data in parser, return message + * + * @param[out] msg The detected message frame + * + * @returns true if a message was detected, false otherwise (meaning: not enough data in parser) + */ + bool Process(ParserMsg& msg); + + /** + * @brief Get remaining data from parser as OTHER message(s) + * + * @param[out] msg A chunk of the remaining data as a OTHER message + * + * @returns true if there was remaining data, false if parser buffer was empty + */ + bool Flush(ParserMsg& msg); + + // + // ----- Utilities ------------------------------------------------------------------------------------------------- + + /** + * @brief Get parser statistics + * + * @returns a copy of the parser statistics + */ + ParserStats GetStats() const; + + // + // ----- Private --------------------------------------------------------------------------------------------------- + private: + // Parser state + // clang-format off + uint8_t buf_[MAX_ADD_SIZE + (2 * MAX_ANY_SIZE)]; //!< Parser buffer + std::size_t size_; //!< Buffer size (size of data that is available for processing) + std::size_t offs_; //!< Buffer offset (points to start of data to be processed) + ParserStats stats_; //!< Statistics + // clang-format on + + void EmitMessage(ParserMsg&, const std::size_t, const Protocol); //!< Helper to emit a normal message + void EmitGarbage(ParserMsg&); //!< Helper to emit a OTHER message +}; + /* ****************************************************************************************************************** */ } // namespace parser } // namespace common diff --git a/fpsdk_common/include/fpsdk_common/parser/.gitkeep b/fpsdk_common/include/fpsdk_common/parser/.gitkeep deleted file mode 100644 index e69de29..0000000 diff --git a/fpsdk_common/include/fpsdk_common/parser/crc.hpp b/fpsdk_common/include/fpsdk_common/parser/crc.hpp new file mode 100644 index 0000000..072c955 --- /dev/null +++ b/fpsdk_common/include/fpsdk_common/parser/crc.hpp @@ -0,0 +1,124 @@ +/** + * \verbatim + * ___ ___ + * \ \ / / + * \ \/ / Copyright (c) Fixposition AG (www.fixposition.com) and contributors + * / /\ \ License: see the LICENSE file + * /__/ \__\ + * + * Based on work by flipflip (https://github.com/phkehl) + * \endverbatim + * + * @file + * @brief Fixposition SDK: Parser CRC routines + * + * @page FPSDK_COMMON_PARSER_CRC Parser CRC routines + * + * **API**: fpsdk_common/parser/crc.hpp and fpsdk::common::parser::crc + * + */ +#ifndef __FPSDK_COMMON_PARSER_CRC_HPP__ +#define __FPSDK_COMMON_PARSER_CRC_HPP__ + +/* LIBC/STL */ +#include + +/* EXTERNAL */ + +/* PACKAGE */ + +namespace fpsdk { +namespace common { +namespace parser { +/** + * @brief Parser NOV_B routines and types + */ +namespace crc { +/* ****************************************************************************************************************** */ + +/** + * @brief Calculate 32-bit CRC as used by FP_B + * + * @param[in] data Pointer to the data to calculate the CRC for + * @param[in] size Size of data + * + * @returns the CRC + */ +uint32_t Crc32fpb(const uint8_t* data, const std::size_t size); + +/** + * @brief Calculate 24-bit CRC as used by RTCM3 and SPARTN + * + * @param[in] data Pointer to the data to calculate the CRC for + * @param[in] size Size of data + * + * @returns the CRC (32-bit value masked with 0x00ffffff) + */ +uint32_t Crc24rtcm3(const uint8_t* data, const std::size_t size); + +/** + * @brief Calculate 32-bit CRC as used by NOV_B (and UNI_B) + * + * @param[in] data Pointer to the data to calculate the CRC for + * @param[in] size Size of data + * + * @returns the CRC + */ +uint32_t Crc32novb(const uint8_t* data, const std::size_t size); + +/** + * @brief Calculate 4-bit CRC as used by SPARTN + * + * @param[in] data Pointer to the data to calculate the CRC for + * @param[in] size Size of data + + \returns CRC (8-bit value masked with 0x0f) +*/ +uint8_t Crc4spartn(const uint8_t* data, const std::size_t size); + +/** + * @brief Calculate 8-bit CRC as used by SPARTN + * + * @param[in] data Pointer to the data to calculate the CRC for + * @param[in] size Size of data + * + * @returns the CRC + */ +uint8_t Crc8spartn(const uint8_t* data, const std::size_t size); + +/** + * @brief Calculate 16-bit CRC as used by SPARTN + * + * @param[in] data Pointer to the data to calculate the CRC for + * @param[in] size Size of data + * + * @returns the CRC (result undefined if size <= 0 or data == NULL) + */ +uint16_t Crc16spartn(const uint8_t* data, const std::size_t size); + +/** + * @brief Calculate 32-bit CRC as used by SPARTN + * + * @param[in] data Pointer to the data to calculate the CRC for + * @param[in] size Size of data + * + * @returns the CRC + */ +uint32_t Crc32spartn(const uint8_t* data, const std::size_t size); + +/** + * @brief Calculate 16-bit checksum as used by UBX + * + * @param[in] data Pointer to the data to calculate the CRC for + * @param[in] size Size of data + * + * @returns the checksum + */ +uint16_t ChecksumUbx(const uint8_t* data, const std::size_t size); + +/* ****************************************************************************************************************** */ +} // namespace crc +} // namespace parser +} // namespace common +} // namespace fpsdk +#endif // __FPSDK_COMMON_PARSER_CRC_HPP__ diff --git a/fpsdk_common/include/fpsdk_common/parser/fpa.hpp b/fpsdk_common/include/fpsdk_common/parser/fpa.hpp new file mode 100644 index 0000000..854cafa --- /dev/null +++ b/fpsdk_common/include/fpsdk_common/parser/fpa.hpp @@ -0,0 +1,884 @@ +/** + * \verbatim + * ___ ___ + * \ \ / / + * \ \/ / Copyright (c) Fixposition AG (www.fixposition.com) and contributors + * / /\ \ License: see the LICENSE file + * /__/ \__\ + * + * Based on work by flipflip (https://github.com/phkehl) + * \endverbatim + * + * @file + * @brief Fixposition SDK: Parser FP_A routines and types + */ +// clang-format off +/** + * @page FPSDK_COMMON_PARSER_FPA Parser FP_A routines and types + * + * **API**: fpsdk_common/parser/fpa.hpp and fpsdk::common::parser::fpa + * + * @fp_msgspec_begin{FP_A-Protocol} + * + * Messages are in this form: + * + * $FP,msg_type,msg_version,field3,field4,…,fieldN*CC\\r\\n + * + * Where: + * + * - The FP_A style framing: + * - \$ + * -- Start character ("$", ASCII 36) + * - \*CC + * -- Checksum: "*" (ASCII 42) and two digit XOR value of all payload + * characters in captial hexadecimal notation, for example: + * "FPX" = 'F' ^ 'P' ^ 'X' = 70 ^ 80 ^ 88 = 78 = 0x4e = checksum 4E + * - \\r\\n -- Message termination characters (CR + LF, ASCII 13 + 10) + * - A Fixposition identifier: + * - FP + * -- Fixposition ASCII message identifier, "FP" (ASCII 70 + 80) + * - Fixposition message type and version: + * - msg_type (= field1) + * -- Message type, all capital letters (ASCII 65--90) + * - msg_version (= field2) + * -- Message version, decimal number (letters 0--9, ASCII 48--57), range 1--… + * - Data fields (payload) + * - field3,field4,…,fieldN + * -- The structure of the message data is defined by the msg_type + * and version. + * Each field can contain all printable 7-bit ASCII characters (ASCII 32–126), excluding the + * reserved characters `!` (ASCII 33), `$` (ASCII 36), `*` (ASCII 42), `,` (ASCII 44), + * `\` (ASCII 92), `~` (ASCII 126). + * - Field separators + * - All fields (identifier, message type, message version, data fields) are separated by a `,` (comma, ASCII 44) + * - Null fields + * - Data fields can be _null_, meaning their value is absent to indicate that no data is + * available. The data for null fields is the empty string. For example: + * - Definition: …,fieldi,fieldi+1,fieldi+2,… + * - Values: fieldi = 123, fieldi+1 = _null_, + * fieldi+2 = 456 + * - Payload string: …,123,,456,… + * - Data field types: + * - _Numeric_: Decimal integer number, one or more digits (0-9) and optional leading "-" sign + * - _Float (.x)_: Decimal floating point number, one or more digits (0-9) and optional leading "-" sign, with + * _x_ digits fractional part separated by a dot (".") + * - _Float (x)_: Decimal floating point number with _x_ significant digits, optional leading "-", optional fractional + * part separated by a dot (".") + * - _String_: String of allowed payload characters (but not the `,` field separator) + * - ... + * - ... + * + * @fp_msgspec_end + * + */ +// clang-format on +#ifndef __FPSDK_COMMON_PARSER_FPA_HPP__ +#define __FPSDK_COMMON_PARSER_FPA_HPP__ + +/* LIBC/STL */ +#include +#include +#include + +/* EXTERNAL */ + +/* PACKAGE */ +#include "../logging.hpp" +#include "../types.hpp" +#include "types.hpp" + +namespace fpsdk { +namespace common { +namespace parser { +/** + * @brief Parser FP_A routines and types + */ +namespace fpa { +/* ****************************************************************************************************************** */ + +static constexpr uint8_t FP_A_PREAMBLE = '$'; //!< FP_A framing preamble +static constexpr int FP_A_FRAME_SIZE = 6; //!< FP_A frame size ("$*cc\r\n") + +//! FP_A message meta data +struct FpaMessageMeta +{ + char msg_type_[40] = { 0 }; //!< Message type (for example, "ODOMETRY"), nul-terminated string + int msg_version_ = 0; //!< Message version (for example, 1), < 0 if unknown + int payload_ix0_ = 0; //!< Index (offset) for start of payload, 0 if no payload available + int payload_ix1_ = 0; //!< Index (offset) for end of payload, 0 if no payload available +}; + +/** + * @brief Get FP_A message meta data + * + * @param[out] meta The meta data + * @param[in] msg Pointer to the FP_A message + * @param[in] msg_size Size of the FP_A message (>= 11) + * + * @note No check on the data provided is done. The caller must ensure that the data is a correct FP_A message. + * + * @returns true if the meta data was successfully extracted, false otherwise + */ +bool FpaGetMessageMeta(FpaMessageMeta& meta, const uint8_t* msg, const std::size_t msg_size); + +/** + * @brief Get FP_A message name + * + * Generates a name (string) in the form "FP_A-MESSAGEID" (for example, "FP_A-ODOMETRY"). + * + * @param[out] name String to write the name to + * @param[in] size Size of \c name (incl. nul termination) + * @param[in] msg Pointer to the FP_A message + * @param[in] msg_size Size of the \c msg + * + * @note No check on the data provided is done. The caller must ensure that the data is a valid FP_A or FP_A message. + * + * @returns true if message name was generated, false if \c name buffer was too small + */ +bool FpaGetMessageName(char* name, const std::size_t size, const uint8_t* msg, const std::size_t msg_size); + +/** + * @brief Get FP_A message info + * + * This stringifies the content of some FP_A messages, for debugging. + * + * @param[out] info String to write the info to + * @param[in] size Size of \c name (incl. nul termination) + * @param[in] msg Pointer to the FP_A message + * @param[in] msg_size Size of the \c msg + * + * @note No check on the data provided is done. The caller must ensure that the data is a valid FP_A message. + * + * @returns true if message info was generated (even if info is empty), false if \c name buffer was too small + */ +bool FpaGetMessageInfo(char* info, const std::size_t size, const uint8_t* msg, const std::size_t msg_size); + +/** + * @brief FP_A fusion initialisation status + */ +enum class FpaInitStatus : int +{ // clang-format off + UNSPECIFIED = '?', //!< Unspecified + NOT_INIT = '0', //!< Not initialised + LOCAL_INIT = '1', //!< Locally initialised + GLOBAL_INIT = '2', //!< Globally initialised +}; // clang-format on + +/** + * @brief FP_A legacy fusion status + */ +enum class FpaFusionStatusLegacy : int +{ // clang-format off + UNSPECIFIED = '?', //!< Unspecified + NONE = '0', //!< Not started + VISION = '1', //!< Vision only + VIO = '2', //!< Visual-inertial fusion + IMU_GNSS = '3', //!< Inertial-GNSS fusion + VIO_GNSS = '4' //!< Visual-inertial-GNSS fusion +}; //clang-format on + +/** + * @brief FP_A fusion measurement status + */ +enum class FpaMeasStatus : int +{ // clang-format off + UNSPECIFIED = '?', //!< Unspecified + NOT_USED = '0', //!< Not used + USED = '1', //!< Used + DEGRADED = '2', //!< Degraded +}; // clang-format on + +/** + * @brief FP_A IMU bias status + */ +enum class FpaImuStatus : int +{ // clang-format off + UNSPECIFIED = '?', //!< Unspecified + NOT_CONVERGED = '0', //!< Not converged + WARMSTARTED = '1', //!< Warmstarted + ROUGH_CONVERGED = '2', //!< Rough convergence + FINE_CONVERGED = '3', //!< Fine convergence +}; // clang-format on + +/** + * @brief FP_A Legacy IMU bias status + */ +enum class FpaImuStatusLegacy : int +{ // clang-format off + UNSPECIFIED = '?', //!< Unspecified + NOT_CONVERGED = '0', //!< Not converged + CONVERGED = '1', //!< Converged +}; // clang-format on + +/** + * @brief FP_A IMU variance + */ +enum class FpaImuNoise : int +{ // clang-format off + UNSPECIFIED = '?', //!< Unspecified + LOW_NOISE = '1', //!< Low noise + MEDIUM_NOISE = '2', //!< Medium noise + HIGH_NOISE = '3', //!< High noise + RESERVED4 = '4', //!< Reserved + RESERVED5 = '5', //!< Reserved + RESERVED6 = '6', //!< Reserved + RESERVED7 = '7', //!< Reserved +}; // clang-format on + +/** + * @brief FP_A IMU accelerometer and gyroscope convergence + */ +enum class FpaImuConv : int +{ // clang-format off + UNSPECIFIED = '?', //!< Unspecified + RESERVED0 = '0', //!< Reserved + WAIT_IMU_MEAS = '1', //!< Awaiting IMU measurements + WAIT_GLOBAL_MEAS = '2', //!< Insufficient global measurements + WAIT_MOTION = '3', //!< Insufficient motion + CONVERGING = '4', //!< Converging + RESERVED5 = '5', //!< Reserved + RESERVED6 = '6', //!< Reserved + IDLE = '7', //!< Idle +}; // clang-format on + +/** + * @brief FP_A GNSS fix status + */ +enum class FpaGnssStatus : int +{ // clang-format off + UNSPECIFIED = '?', //!< Unspecified + NO_FIX = '0', //!< No fix + SPP = '1', //!< Single-point positioning (SPP) + RTK_MB = '2', //!< RTK moving baseline + RESERVED3 = '3', //!< Reserved + RESERVED4 = '4', //!< Reserved + RTK_FLOAT = '5', //!< RTK float + RESERVED6 = '6', //!< Reserved + RESERVED7 = '7', //!< Reserved + RTK_FIXED = '8', //!< RTK fixed + RESERVED9 = '9', //!< Reserved +}; // clang-format on + +/** + * @brief FP_A GNSS correction status + */ +enum class FpaCorrStatus : int +{ // clang-format off + UNSPECIFIED = '?', //!< Unspecified + WAITING_FUSION = '0', //!< Waiting fusion + NO_GNSS = '1', //!< No GNSS available + NO_CORR = '2', //!< No corrections used + LIMITED_CORR = '3', //!< Limited corrections used: station data & at least one of the constellations (both bands) among the valid rover measurements + OLD_CORR = '4', //!< Corrections are too old (TBD) + GOOD_CORR = '5', //!< Sufficient corrections used: station data and corrections for ALL bands among the valid rover measurements + RESERVED6 = '6', //!< Reserved + RESERVED7 = '7', //!< Reserved + RESERVED8 = '8', //!< Reserved + RESERVED9 = '9', //!< Reserved +}; // clang-format on + +/** + * @brief FP_A baseline status + */ +enum class FpaBaselineStatus : int +{ // clang-format off + UNSPECIFIED = '?', //!< Unspecified + WAITING_FUSION = '0', //!< Waiting fusion + NO_FIX = '1', //!< Not available or no fix + FAILING = '2', //!< Failing + PASSING = '3', //!< Passing +}; // clang-format on + +/** + * @brief FP_A camera status + */ +enum class FpaCamStatus : int +{ // clang-format off + UNSPECIFIED = '?', //!< Unspecified + CAM_UNAVL = '0', //!< Camera not available + BAD_FEAT = '1', //!< Camera available, but not usable (e.g. too dark) + RESERVED2 = '2', //!< Reserved + RESERVED3 = '3', //!< Reserved + RESERVED4 = '4', //!< Reserved + GOOD = '5', //!< Camera working and available +}; // clang-format on + +/** + * @brief FP_A wheelspeed status + */ +enum class FpaWsStatus : int +{ // clang-format off + UNSPECIFIED = '?', //!< Unspecified + NOT_ENABLED = '0', //!< No wheelspeed enabled + MISS_MEAS = '1', //!< Missing wheelspeed measurements + NONE_CONVERGED = '2', //!< At least one wheelspeed enabled, no wheelspeed converged + ONE_CONVERGED = '3', //!< At least one wheelspeed enabled and at least one converged + ALL_CONVERGED = '4', //!< At least one wheelspeed enabled and all converged +}; // clang-format on + +/** + * @brief FP_A Legacy wheelspeed status + */ +enum class FpaWsStatusLegacy : int +{ // clang-format off + UNSPECIFIED = '?', //!< Unspecified + NOT_ENABLED = '-', //!< No wheelspeed enabled + NONE_CONVERGED = '0', //!< None converged + ONE_OR_MORE_CONVERGED = '1', //!< At least one converged +}; // clang-format on + +/** + * @brief FP_A wheelspeed convergence status + */ +enum class FpaWsConv : int +{ // clang-format off + UNSPECIFIED = '?', //!< Unspecified + WAIT_FUSION = '0', //!< Awaiting Fusion + WAIT_WS_MEAS = '1', //!< Missing wheelspeed measurements + WAIT_GLOBAL_MEAS = '2', //!< Insufficient global measurements + WAIT_MOTION = '3', //!< Insufficient motion + WAIT_IMU_BIAS = '4', //!< Insufficient imu bias convergence + CONVERGING = '5', //!< Converging + IDLE = '6', //!< Idle +}; // clang-format on + +/** + * @brief FP_A markers status + */ +enum class FpaMarkersStatus : int +{ // clang-format off + UNSPECIFIED = '?', //!< Unspecified + NOT_ENABLED = '0', //!< No markers available + NONE_CONVERGED = '1', //!< Markers available + ONE_CONVERGED = '2', //!< Markers available and used + ALL_CONVERGED = '3', //!< All markers available and used +}; // clang-format on + +/** + * @brief FP_A markers convergence status + */ +enum class FpaMarkersConv : int +{ // clang-format off + UNSPECIFIED = '?', //!< Unspecified + WAIT_FUSION = '0', //!< Awaiting Fusion + WAIT_MARKER_MEAS = '1', //!< Waiting marker measurements + WAIT_GLOBAL_MEAS = '2', //!< Insufficient global measurements + CONVERGING = '3', //!< Converging + IDLE = '4', //!< Idle +}; // clang-format on + +/** + * @brief FP_A GNSS fix type + */ +enum class FpaGnssFix : int +{ // clang-format off + UNSPECIFIED = '?', //!< Unspecified + UNKNOWN = '0', //!< Unknown + NOFIX = '1', //!< No fix + DRONLY = '2', //!< Dead-reckoning only + TIME = '3', //!< Time-only fix + S2D = '4', //!< Single 2D fix + S3D = '5', //!< Single 3D fix + S3D_DR = '6', //!< Single 3D fix with dead-reckoning + RTK_FLOAT = '7', //!< RTK float fix + RTK_FIXED = '8', //!< RTK fixed fix +}; // clang-format on + +/** + * @brief FP_A epoch type + */ +enum class FpaEpoch : int +{ + UNSPECIFIED = 0, //!< Unspecified + GNSS1, //!< GNSS 1 + GNSS2, //!< GNSS 2 + GNSS, //!< Combined GNSS + FUSION, //!< Fusion +}; + +/** + * @brief FP_A GNSS antenna state + */ +enum class FpaAntState : int +{ + UNSPECIFIED = 0, //!< Unspecified + OK, //!< Antenna detected and good + OPEN, //!< No antenna detected (or connected via DC block) + SHORT, //!< Antenna short circuit detected +}; + +/** + * @brief FP_A GNSS antenna power + */ +enum class FpaAntPower : int +{ + UNSPECIFIED = 0, //!< Unspecified + ON, //!< Antenna power supply is on + OFF, //!< Antenna power supply is off +}; + +/** + * @brief FP_A text levels + */ +enum class FpaTextLevel : int +{ // clang-format off + UNSPECIFIED = 0, //!< Unspecified + ERROR = types::EnumToVal(logging::LoggingLevel::ERROR), //!< Error + WARNING = types::EnumToVal(logging::LoggingLevel::WARNING), //!< Warning + INFO = types::EnumToVal(logging::LoggingLevel::INFO), //!< Info + DEBUG = types::EnumToVal(logging::LoggingLevel::DEBUG), //!< Debug +}; // clang-format on +/** + * @brief FP_A time base + */ +enum class FpaTimebase : int +{ // clang-format off + UNSPECIFIED = 0, //!< Unspecified + NONE, //!< None + GNSS, //!< GNSS + UTC, //!< UTC +}; // clang-format on + +/** + * @brief FP_A time reference + */ +enum class FpaTimeref : int +{ // clang-format off + UNSPECIFIED = 0, //!< Unspecified + UTC_NONE, //!< UTC: None (UTC params not yet known) + UTC_CRL, //!< UTC: Communications Research Laboratory (CRL), Japan + UTC_NIST, //!< UTC: National Institute of Standards and Technology (NIST) + UTC_USNO, //!< UTC: U.S. Naval Observatory (USNO) + UTC_BIPM, //!< UTC: International Bureau of Weights and Measures (BIPM) + UTC_EU, //!< UTC: European laboratories + UTC_SU, //!< UTC: Former Soviet Union (SU) + UTC_NTSC, //!< UTC: National Time Service Center (NTSC), China + GNSS_GPS, //!< GNSS: GPS + GNSS_GAL, //!< GNSS: Galileo + GNSS_BDS, //!< GNSS: BeiDou + GNSS_GLO, //!< GNSS: GLONASS + GNSS_NVC, //!< GNSS: NavIC + OTHER, //!< other/unknown GNSS/UTC +}; // clang-format on + +/** + * @brief FP_A integer value + */ +struct FpaInt +{ + bool valid = false; //!< Data is valid + int value = 0; //!< Value +}; + +/** + * @brief FP_A float value + */ +struct FpaFloat +{ + bool valid = false; //!< Data is valid + double value = 0.0; //!< Value +}; + +/** + * @brief FP_A three float values + */ +struct FpaFloat3 +{ + bool valid = false; //!< Data is valid + std::array values = { { 0.0, 0.0, 0.0 } }; //!< Values +}; + +/** + * @brief FP_A four float values + */ +struct FpaFloat4 +{ + bool valid = false; //!< Data is valid + std::array values = { { 0.0, 0.0, 0.0, 0.0 } }; //!< Values +}; + +/** + * @brief FP_A six float values + */ +struct FpaFloat6 +{ + bool valid = false; //!< Data is valid + std::array values = { { 0.0, 0.0, 0.0, 0.0, 0.0, 0.0 } }; //!< Values +}; + +/** + * @brief FP_A GPS time + */ +struct FpaGpsTime +{ + FpaInt week; //!< GPS week number, range 0-9999, or null if time not (yet) available + FpaFloat tow; //!< GPS time of week, range 0.000-604799.999999, or null if time not (yet) available + + bool operator==(const FpaGpsTime& rhs) const; //!< Equal (epsilon = 1e-6) + bool operator!=(const FpaGpsTime& rhs) const; //!< Not equal (epsilon = 1e-6) + bool operator<(const FpaGpsTime& rhs) const; //!< Less than + bool operator>(const FpaGpsTime& rhs) const; //!< Greater than + bool operator<=(const FpaGpsTime& rhs) const; //!< Less or equal than + bool operator>=(const FpaGpsTime& rhs) const; //!< Greater or equal than +}; + +/** + * @brief FP_A-EOE (version 1) message payload + */ +struct FpaEoePayload +{ + FpaGpsTime gps_time; //!< Time + FpaEpoch epoch = FpaEpoch::UNSPECIFIED; //!< Indicates which epoch ended ("FUSION", "GNSS", "GNSS1", "GNSS2") + + /** + * @brief Set data from message + * + * @param[in] msg Pointer to the FP_A message + * @param[in] msg_size Size of the FP_A message (>= 11) + * + * @returns true if sentence payload was correct and all data could be extracted (fields are now valid), or false + * otherwise (fields are now invalid) + */ + bool SetFromMsg(const uint8_t* msg, const std::size_t msg_size); +}; + +/** + * @brief FP_A-GNSSANT (version 1) message payload + */ +struct FpaGnssantPayload +{ // clang-format off + FpaGpsTime gps_time; //!< Time + FpaAntState gnss1_state = FpaAntState::UNSPECIFIED; //!< GNSS1 antenna state + FpaAntPower gnss1_power = FpaAntPower::UNSPECIFIED; //!< GNSS1 antenna power + FpaInt gnss1_age; //!< Time since gnss1_state or gnss1_power information last changed, 0-604800 + FpaAntState gnss2_state = FpaAntState::UNSPECIFIED; //!< GNSS2 antenna state + FpaAntPower gnss2_power = FpaAntPower::UNSPECIFIED; //!< GNSS2 antenna power + FpaInt gnss2_age; //!< Time since gnss2_state or gnss2_power information last changed, 0-604800 + // clang-format on + + /** + * @brief Set data from message + * + * @param[in] msg Pointer to the FP_A message + * @param[in] msg_size Size of the FP_A message (>= 11) + * + * @returns true if sentence payload was correct and all data could be extracted (fields are now valid), or false + * otherwise (fields are now invalid) + */ + bool SetFromMsg(const uint8_t* msg, const std::size_t msg_size); +}; + +/** + * @brief FP_A-GNSSCORR (version 1) message payload + */ +struct FpaGnsscorrPayload +{ // clang-format off + FpaGpsTime gps_time; //!< Time + FpaGnssFix gnss1_fix = FpaGnssFix::UNSPECIFIED; //!< Fix status of GNSS1 + FpaInt gnss1_nsig_l1; //!< Number of L1 signals with correction data tracked by GNSS1 receiver, range 0-100 + FpaInt gnss1_nsig_l2; //!< Number of L2 signals with correction data tracked by GNSS1 receiver, range 0-100 + FpaGnssFix gnss2_fix = FpaGnssFix::UNSPECIFIED; //!< Fix status of GNSS2 receiver + FpaInt gnss2_nsig_l1; //!< Number of L1 signals with correction data tracked by GNSS2 receiver, range 0-100 + FpaInt gnss2_nsig_l2; //!< Number of L2 signals with correction data tracked by GNSS2 receiver, range 0-100 + FpaFloat corr_latency; //!< Average correction data latency (10s window), range 0.0-99.9 + FpaFloat corr_update_rate; //!< Average correction update rate (10s window), range 0.0-0.0 + FpaFloat corr_data_rate; //!< Average correction data rate (10s window), range 0.0-50.0 + FpaFloat corr_msg_rate; //!< Average correction message rate (10s window), range 0-50 + FpaInt sta_id; //!< Correction station ID, range 0--4095 + FpaFloat3 sta_llh; //!< Correction station latitude/longitude/height [deg, deg, m] + FpaInt sta_dist; //!< Correction station baseline length (approximate 3d distance), range 0-100000 + // clang-format on + + /** + * @brief Set data from message + * + * @param[in] msg Pointer to the FP_A message + * @param[in] msg_size Size of the FP_A message (>= 11) + * + * @returns true if sentence payload was correct and all data could be extracted (fields are now valid), or false + * otherwise (fields are now invalid) + */ + bool SetFromMsg(const uint8_t* msg, const std::size_t msg_size); +}; + +/** + * @brief FP_A-...IMU (version 1) messages payload + */ +struct FpaImuPayload +{ + //! Data from which FP_A-...IMU is stored + enum class Which + { + UNSPECIFIED, //!< Unspecified + FP_A_RAWIMU, //!< Data is from FP_A-RAWIMU + FP_A_CORRIMU, //!< Data is from FP_A-CORRIMU + }; + Which which = Which::UNSPECIFIED; //!< Indicates from which message the data is + // clang-format off + FpaGpsTime gps_time; //!< Time + FpaFloat3 acc; //!< Raw acceleration in output frame, X/Y/Z components + FpaFloat3 rot; //!< Raw angular velocity in output frame, X/Y/Z components + // clang-format on + + /** + * @brief Set data from message + * + * @param[in] msg Pointer to the FP_A message + * @param[in] msg_size Size of the FP_A message (>= 11) + * + * @returns true if sentence payload was correct and all data could be extracted (fields are now valid), or false + * otherwise (fields are now invalid) + */ + virtual bool SetFromMsg(const uint8_t* msg, const std::size_t msg_size) = 0; +}; + +/** + * @brief FP_A-RAWIMU (version 1) message payload + */ +struct FpaRawimuPayload : public FpaImuPayload +{ + bool SetFromMsg(const uint8_t* msg, const std::size_t msg_size) final; +}; + +/** + * @brief FP_A-CORRIMU (version 1) message payload + */ +struct FpaCorrimuPayload : public FpaImuPayload +{ + bool SetFromMsg(const uint8_t* msg, const std::size_t msg_size) final; +}; + +/** + * @brief FP_A-IMUBIAS (version 1) message payload + */ +struct FpaImubiasPayload +{ // clang-format off + FpaGpsTime gps_time; //!< Time + FpaMeasStatus fusion_imu; //!< Fusion measurement status: IMU + FpaImuStatus imu_status; //!< IMU bias status + FpaImuNoise imu_noise; //!< IMU variance status + FpaImuConv imu_conv; //!< IMU convergence status + FpaFloat3 bias_acc; //!< Accelerometer bias, X/Y/Z components + FpaFloat3 bias_gyr; //!< Gyroscope bias, X/Y/Z components + FpaFloat3 bias_cov_acc; //!< Accelerometer bias covariance, X/Y/Z components + FpaFloat3 bias_cov_gyr; //!< Gyroscope bias covariance, X/Y/Z components + // clang-format on + + /** + * @brief Set data from message + * + * @param[in] msg Pointer to the FP_A message + * @param[in] msg_size Size of the FP_A message (>= 11) + * + * @returns true if sentence payload was correct and all data could be extracted (fields are now valid), or false + * otherwise (fields are now invalid) + */ + bool SetFromMsg(const uint8_t* msg, const std::size_t msg_size); +}; + +/** + * @brief FP_A-LLH (version 1) message payload + */ +struct FpaLlhPayload +{ // clang-format off + FpaGpsTime gps_time; //!< Time + FpaFloat3 llh; //!< Latitude/longitude/height [deg, deg, m] + FpaFloat6 cov_enu; //!< Position covariance in ENU, EE/NN/UU/EN/NU/EU components [m^2] + // clang-format on + + /** + * @brief Set data from message + * + * @param[in] msg Pointer to the FP_A message + * @param[in] msg_size Size of the FP_A message (>= 11) + * + * @returns true if sentence payload was correct and all data could be extracted (fields are now valid), or false + * otherwise (fields are now invalid) + */ + bool SetFromMsg(const uint8_t* msg, const std::size_t msg_size); +}; + +/** + * @brief FP_A-ODOM... (version 1) messages payload + */ +struct FpaOdomPayload +{ + //! Data from which FP_A-...IMU is stored + enum class Which + { + UNSPECIFIED, //!< Unspecified + FP_A_ODOMETRY, //!< Data is from FP_A-ODOMETRY + FP_A_ODOMENU, //!< Data is from FP_A-ODOMENU + FP_A_ODOMSH, //!< Data is from FP_A-ODOMSH + }; + // clang-format off + Which which = Which::UNSPECIFIED; //!< Indicates from which message the data is + FpaGpsTime gps_time; //!< Time + FpaFloat3 pos; //!< Position, X/Y/Z components + FpaFloat4 orientation; //!< Quaternion, W/X/Y/Z components + FpaFloat3 vel; //!< Velocity, X/Y/Z components + FpaFloat3 rot; //!< Bias corrected angular velocity, X/Y/Z components + FpaFloat3 acc; //!< Bias corrected acceleration, X/Y/Z components + FpaFusionStatusLegacy fusion_status; //!< Fustion status + FpaImuStatusLegacy imu_bias_status; //!< IMU bias status + FpaGnssFix gnss1_fix; //!< Fix status of GNSS1 receiver + FpaGnssFix gnss2_fix; //!< Fix status of GNSS2 receiver + FpaWsStatusLegacy wheelspeed_status; //!< Wheelspeed status + FpaFloat6 pos_cov; //!< Position covariance, XX/YY/ZZ/XY/YZ/XZ components + FpaFloat6 orientation_cov; //!< Orientation covariance, XX/YY/ZZ/XY/YZ/XZ components + FpaFloat6 vel_cov; //!< Velocity covariance, XX/YY/ZZ/XY/YZ/XZ components + // clang-format on + + /** + * @brief Set data from message + * + * @param[in] msg Pointer to the FP_A message + * @param[in] msg_size Size of the FP_A message (>= 11) + * + * @returns true if sentence payload was correct and all data could be extracted (fields are now valid), or false + * otherwise (fields are now invalid) + */ + virtual bool SetFromMsg(const uint8_t* msg, const std::size_t msg_size) = 0; +}; + +/** + * @brief FP_A-ODOMETRY (version 2) messages payload (ECEF) + */ +struct FpaOdometryPayload : public FpaOdomPayload +{ + bool SetFromMsg(const uint8_t* msg, const std::size_t msg_size) final; +}; + +/** + * @brief FP_A-ODOMENU (version 1) messages payload (ENU0) + */ +struct FpaOdomenuPayload : public FpaOdomPayload +{ + bool SetFromMsg(const uint8_t* msg, const std::size_t msg_size) final; +}; + +/** + * @brief FP_A-ODOMSH (version 1) messages payload (ECEF) + */ +struct FpaOdomshPayload : public FpaOdomPayload +{ + bool SetFromMsg(const uint8_t* msg, const std::size_t msg_size) final; +}; + +/** + * @brief FP_A-ODOMSTATUS (version 1) messages payload + */ +struct FpaOdomstatusPayload +{ // clang-format off + FpaGpsTime gps_time; //!< Time + FpaInitStatus init_status; //!< Fusion init status + FpaMeasStatus fusion_imu; //!< Fusion measurement status: IMU + FpaMeasStatus fusion_gnss1; //!< Fusion measurement status: GNSS 1 + FpaMeasStatus fusion_gnss2; //!< Fusion measurement status: GNSS 2 + FpaMeasStatus fusion_corr; //!< Fusion measurement status: GNSS corrections + FpaMeasStatus fusion_cam1; //!< Fusion measurement status: camera + FpaMeasStatus fusion_ws; //!< Fusion measurement status: wheelspeed + FpaMeasStatus fusion_markers; //!< Fusion measurement status: markers + FpaImuStatus imu_status; //!< IMU bias status + FpaImuNoise imu_noise; //!< IMU variance status + FpaImuConv imu_conv; //!< IMU convergence status + FpaGnssStatus gnss1_status; //!< GNSS 1 status + FpaGnssStatus gnss2_status; //!< GNSS 2 status + FpaBaselineStatus baseline_status; //!< Baseline status + FpaCorrStatus corr_status; //!< GNSS correction status + FpaCamStatus cam1_status; //!< Camera 1 status + FpaWsStatus ws_status; //!< Wheelspeed status + FpaWsConv ws_conv; //!< Wheelspeed convergence status + FpaMarkersStatus markers_status; //!< Marker status + FpaMarkersConv markers_conv; //!< Marker convergence status + // clang-format on + + /** + * @brief Set data from message + * + * @param[in] msg Pointer to the FP_A message + * @param[in] msg_size Size of the FP_A message (>= 11) + * + * @returns true if sentence payload was correct and all data could be extracted (fields are now valid), or false + * otherwise (fields are now invalid) + */ + bool SetFromMsg(const uint8_t* msg, const std::size_t msg_size); +}; + +/** + * @brief FP_A-TEXT (version 1) message payload + */ +struct FpaTextPayload +{ // clang-format off + FpaTextLevel level; //!< Level + char text[MAX_FP_A_SIZE] = { 0 }; //!< Text (nul-terminated string) + // clang-format on + + /** + * @brief Set data from message + * + * @param[in] msg Pointer to the FP_A message + * @param[in] msg_size Size of the FP_A message (>= 11) + * + * @returns true if sentence payload was correct and all data could be extracted (fields are now valid), or false + * otherwise (fields are now invalid) + */ + bool SetFromMsg(const uint8_t* msg, const std::size_t msg_size); +}; + +/** + * @brief FP_A-TF (version 2) message payload + */ +struct FpaTfPayload +{ // clang-format off + FpaGpsTime gps_time; //!< Time + char frame_a[10] = { 0 }; //!< Target frame (nul-terminated string) + char frame_b[10] = { 0 }; //!< Initial frame (nul-terminated string) + FpaFloat3 translation; //!< Translation, X/Y/Z components + FpaFloat4 orientation; //!< Rotation in quaternion, W/X/Y/Z components + // clang-format on + + /** + * @brief Set data from message + * + * @param[in] msg Pointer to the FP_A message + * @param[in] msg_size Size of the FP_A message (>= 11) + * + * @returns true if sentence payload was correct and all data could be extracted (fields are now valid), or false + * otherwise (fields are now invalid) + */ + bool SetFromMsg(const uint8_t* msg, const std::size_t msg_size); +}; + +/** + * @brief FP_A-TP (version 1) message payload + */ +struct FpaTpPayload +{ // clang-format off + FpaGpsTime gps_time; //!< Time + char tp_name[10] = { 0 }; //!< Timebulse name (nul-terminated string) + FpaTimebase timebase = FpaTimebase::UNSPECIFIED; //!< Time base + FpaTimeref timeref = FpaTimeref::UNSPECIFIED; //!< Time reference + FpaInt tp_tow_sec; //!< Timepulse time seconds of week, integer second part (0--604799) + FpaFloat tp_tow_psec; //!< Timepulse time seconds of week, sub-second part (0.000000000000--0.999999999999) + FpaInt gps_leaps; //!< GPS leapseconds + // clang-format on + + /** + * @brief Set data from message + * + * @param[in] msg Pointer to the FP_A message + * @param[in] msg_size Size of the FP_A message (>= 11) + * + * @returns true if sentence payload was correct and all data could be extracted (fields are now valid), or false + * otherwise (fields are now invalid) + */ + bool SetFromMsg(const uint8_t* msg, const std::size_t msg_size); +}; + +/* ****************************************************************************************************************** */ +} // namespace fpa +} // namespace parser +} // namespace common +} // namespace fpsdk +#endif // __FPSDK_COMMON_PARSER_FPA_HPP__ diff --git a/fpsdk_common/include/fpsdk_common/parser/fpb.hpp b/fpsdk_common/include/fpsdk_common/parser/fpb.hpp new file mode 100644 index 0000000..3ca1fe5 --- /dev/null +++ b/fpsdk_common/include/fpsdk_common/parser/fpb.hpp @@ -0,0 +1,448 @@ +/** + * \verbatim + * ___ ___ + * \ \ / / + * \ \/ / Copyright (c) Fixposition AG (www.fixposition.com) and contributors + * / /\ \ License: see the LICENSE file + * /__/ \__\ + * + * Based on work by flipflip (https://github.com/phkehl) + * \endverbatim + * + * @file + * @brief Fixposition SDK: Parser FP_B routines and types + * + * @page FPSDK_COMMON_PARSER_FPB Parser FP_B routines and types + * + * **API**: fpsdk_common/parser/fpb.hpp and fpsdk::common::parser::fpb + * + * @fp_msgspec_begin{FP_B-Protocol} + * + * **Framing:** + * + * The structure of a FP_B message (frame) is: + * + * | Offs | Size | Type | Content | + * |-----:|:----:|----------|-----------------| + * | 0 | 1 | uint8_t | Sync 1: `f` = 102 = 0x66 = 0b0110'0110 | + * | 1 | 1 | uint8_t | Sync 1: `!` = 33 = 0x21 = 0b0010'0001 | + * | 2 | 2 | uint16_t | Message ID (`message_id`), 1...65534 | + * | 4 | 2 | uint16_t | Payload size (`payload_size`) | + * | 6 | 2 | uint16_t | Monotonic time [ms] (`message_time`), overflows/wraps around at ~65s | + * | 8… | … | … | Payload | + * | 8 + `payload_size` | 4 | uint32_t | Checksum | + * + * The checksum is a 32 bit cyclic redundancy check (CRC) with the polynomial 0x32c00699. See Koopman's *CRC polynomial + * zoo* at for details. + * + * **Payload:** + * + * The payload encoding can be: + * + * - Fixed structure (for example, FP_B-MEASUREMENTS) using little-endian signed and unsigned integers of 8, 16, 32 or + * 64 bits, as well as IEEE 754 single (32 bits) or double (64 bits) precision. + * - Serialised data of a t.b.d. interface description language (e.g. Protobuf, Capn' Proto, Flatbuffers, ....) + * + * **Example:** + * + * A short FP_B frame with the bytes in order they appear on the wire: + * + * First byte Last byte + * | | + * 66 21 34 12 04 00 21 43 01 02 03 04 61 c4 c5 9c + * ^^ ^^ ^^^^^ ^^^^^ ^^^^^ ^^^^^^^^^^^ ^^^^^^^^^^^ + * | | | | | | | + * | | | | | | CRC (= 0x9cc5c461) + * | | | | | Payload (= [ 0x01, 0x02, 0x03, 0x04 ]) + * | | | | Message time (= 0x4321 = 17185 = 17.185s) + * | | | Payload size = (=x0004 = 4) + * | | Message ID (= 0x1234) + * | Sync 2 + * Sync 1 + * + * @fp_msgspec_end + * + * @fp_msgspec_begin{FP_B-Payload-Rules} + * + * **Fixed payload definition:** + * + * A short and incomplete guideline: + * + * - All fields must be aligned + * - Padding must be explicitly added as reserved fields: e.g. `uint8_t reserved[3] //!< Reserved for future use. Set to + * 0.` + * - Fields can only be basic types (no enums!) + * - Decoding must be doable with a single pass. I.e. repeated parts must follow static parts. + * - Repeated parts of the payload mus have a `num_foo` field in the static part. + * - For enums the value 0 must always be "unspecified" or "unknown" + * - Don't use bitfields. Waste some space (e.g. `uint8_t` for a bool, instead of a bit in a bitfield) + * - Values that may or may not be valid must be accompanied by a `foo_valid` flag field. + * - No strings! Not ever. With some exceptions, probably... :-) + * - ...and more... + * + * @fp_msgspec_end + * + */ +#ifndef __FPSDK_COMMON_PARSER_FPB_HPP__ +#define __FPSDK_COMMON_PARSER_FPB_HPP__ + +/* LIBC/STL */ +#include +#include +#include + +/* EXTERNAL */ + +/* PACKAGE */ +#include "../types.hpp" + +namespace fpsdk { +namespace common { +namespace parser { +/** + * @brief Parser FP_B routines and types + */ +namespace fpb { +/* ****************************************************************************************************************** */ + +static constexpr std::size_t FP_B_FRAME_SIZE = 12; //!< Size (in bytes) of FP_B frame +static constexpr std::size_t FP_B_HEAD_SIZE = 8; //!< Size of FP_B frame header +static constexpr uint8_t FP_B_SYNC_1 = 0x66; //!< FP_B frame sync char 1 ('f', 102, 0b0110'0110) +static constexpr uint8_t FP_B_SYNC_2 = 0x21; //!< FP_B frame sync char 2 ('!', 33, 0b0010'0001) + +/** + * @brief Get message ID + * + * @param[in] msg Pointer to the start of the message + * + * @note No check on the data provided is done. The caller must ensure that the data is a valid FP_B message. + * + * @returns message ID + */ +constexpr uint16_t FpbMsgId(const uint8_t* msg) +{ + return (((uint16_t)((uint8_t*)msg)[3] << 8) | (uint16_t)((uint8_t*)msg)[2]); +} + +/** + * @brief Get message time + * + * @param[in] msg Pointer to the start of the message + * + * @note No check on the data provided is done. The caller must ensure that the data is a valid FP_B message. + * + * @returns message time + */ +constexpr uint16_t FpbMsgTime(const uint8_t* msg) +{ + return (((uint16_t)((uint8_t*)msg)[7] << 8) | (uint16_t)((uint8_t*)msg)[6]); +} + +/** + * @brief Get FP_B message name + * + * Generates a name (string) in the form "FP_B-NAME", where NAME is a suitable stringifications of the message ID if + * known (for example, "FP_B-SYSTEMSTATUS", respectively "%05u" formatted message ID if unknown (for example, + * "FP_B-MSG01234"). + * + * @param[out] name String to write the name to + * @param[in] size Size of \c name (incl. nul termination) + * @param[in] msg Pointer to the FP_B message + * @param[in] msg_size Size of the \c msg + * + * @note No check on the data provided is done. The caller must ensure that the data is a valid FP_B message. + * + * @returns true if message name was generated, false if \c name buffer was too small + */ +bool FpbGetMessageName(char* name, const std::size_t size, const uint8_t* msg, const std::size_t msg_size); + +/** + * @brief Get FP_B message info + * + * This stringifies the content of some FP_B messages, for debugging. + * + * @param[out] info String to write the info to + * @param[in] size Size of \c name (incl. nul termination) + * @param[in] msg Pointer to the FP_B message + * @param[in] msg_size Size of the \c msg + * + * @note No check on the data provided is done. The caller must ensure that the data is a valid FP_B message. + * + * @returns true if message info was generated (even if info is empty), false if \c name buffer was too small + */ +bool FpbGetMessageInfo(char* info, const std::size_t size, const uint8_t* msg, const std::size_t msg_size); + +/** + * @brief Make a FP_B message + * + * @param[out] msg The message frame + * @param[in] msg_id Message ID + * @param[in] msg_time Message time [ms] + * @param[in] payload The message payload (up to MAX_FP_B_SIZE - FP_B_FRAME_SIZE bytes, can be empty) + * + * @returns true if the message was successfully constructed (\c msg now contains the message), + * false if failed contructing the message (payload too large) + */ +bool FpbMakeMessage( + std::vector& msg, const uint16_t msg_id, const uint16_t msg_time, const std::vector& payload); + +/** + * @brief Make a FP_B message + * + * @param[out] msg The message frame + * @param[in] msg_id Message ID + * @param[in] msg_time Message time [ms] + * @param[in] payload The message payload (up to MAX_FP_B_SIZE - FP_B_FRAME_SIZE bytes, can be NULL) + * @param[in] payload_size The message payload (up to MAX_FP_B_SIZE - FP_B_FRAME_SIZE, can be 0, even if payload is + * not NULL) + * + * @returns true if the message was successfully constructed (\c msg now contains the message), + * false if failed contructing the message (payload too large, bad arguments) + */ +bool FpbMakeMessage(std::vector& msg, const uint16_t msg_id, const uint16_t msg_time, const uint8_t* payload, + const std::size_t payload_size); + +/** + * @name FP_B messages (names and IDs) + * + * - 1- 999: unused + * - 1000-1999: messages with payload binary serialised data + * - 1101-1199: Fusion + * - 1201-1299: GNSS + * - 1301-1399: System + * - 1401-1499: Configuration + * - 1501-1599: Sensor data + * - 1601-1699: Reserved + * - 1701-1699: Reserved + * - 1801-1699: Reserved + * - 1901-1999: Reserved + * - 2000-3000: messages with static payload + * - 2001-2099: Input data messages (measurements, ...) + * - 2101-2199: Input command message + * - 2201-2299: Input config message + * - 2301-2399: System + * - 2401-2499: Reserved + * - 2501-2599: Reserved + * - 2601-2699: Reserved + * - 2701-2799: Reserved + * - 2801-2899: Reserved + * - 2901-2999: Reserved + * - 3000-65000: Reserved + * - 65001-...: Test messages + * @{ + */ +// clang-format off +// @fp_codegen_begin{FPSDK_COMMON_PARSER_FPB_MESSAGES} +static constexpr uint16_t FP_B_GNSSSTATUS_MSGID = 1201; //!< FP_B-GNSSSTATUS message ID +static constexpr const char* FP_B_GNSSSTATUS_STRID = "FP_B-GNSSSTATUS"; //!< FP_B-GNSSSTATUS message name +static constexpr uint16_t FP_B_SYSTEMSTATUS_MSGID = 1301; //!< FP_B-SYSTEMSTATUS message ID +static constexpr const char* FP_B_SYSTEMSTATUS_STRID = "FP_B-SYSTEMSTATUS"; //!< FP_B-SYSTEMSTATUS message name +static constexpr uint16_t FP_B_MEASUREMENTS_MSGID = 2001; //!< FP_B-MEASUREMENTS message ID +static constexpr const char* FP_B_MEASUREMENTS_STRID = "FP_B-MEASUREMENTS"; //!< FP_B-MEASUREMENTS message name +static constexpr uint16_t FP_B_VERSION_MSGID = 2301; //!< FP_B-VERSION message ID +static constexpr const char* FP_B_VERSION_STRID = "FP_B-VERSION"; //!< FP_B-VERSION message name +static constexpr uint16_t FP_B_UNITTEST1_MSGID = 65001; //!< FP_B-UNITTEST1 message ID +static constexpr const char* FP_B_UNITTEST1_STRID = "FP_B-UNITTEST1"; //!< FP_B-UNITTEST1 message name +static constexpr uint16_t FP_B_UNITTEST2_MSGID = 65002; //!< FP_B-UNITTEST2 message ID +static constexpr const char* FP_B_UNITTEST2_STRID = "FP_B-UNITTEST2"; //!< FP_B-UNITTEST2 message name +// @fp_codegen_end{FPSDK_COMMON_PARSER_FPB_MESSAGES} +// clang-format off +///@} + +// --------------------------------------------------------------------------------------------------------------------- +// clang-format off +// Note: the formatting here is optimised for the wiki, not for Doxygen! +/** + * @name FP_B-MEASUREMENTS + * + * @fp_msgspec_begin{FP_B_MEASUREMENTS} + * + * **Description:** + * + * This message is used to input measurements, such as wheelspeeds, to the sensor. + * + * **Payload fields:** + * + * | # | Offset | Field | Type | Unit | Description | + * |----------:|----------:|-------------------|----------------|------|------------------------------------------------------------------------| + * | 1 | 0 | `version` | uint8_t | - | Version of the FP_B_MEASUREMENTS message (currently 1) | + * | 2 | 1 | `num_meas` | uint8_t | - | Number of measurements present in the body of the message (1…10) | + * | 3 | 2 | `reserved0` | uint8_t[6] | - | Reserved for future use. Set to 0. | + * | | | | | | *The following fields are repeated `num_meas` times (i = 0…`num_meas`-1):* | + * | 4 + i·12 | 8 + i·28 | `meas_x` | int32_t | * | Measurement x axis (for example, [mm/s]) | + * | 5 + i·12 | 12 + i·28 | `meas_y` | int32_t | * | Measurement y axis (for example, [mm/s]) | + * | 6 + i·12 | 16 + i·28 | `meas_z` | int32_t | * | Measurement z axis (for example, [mm/s]) | + * | 7 + i·12 | 20 + i·28 | `meas_x_valid` | uint8_t | - | Validity of `meas_x` (1 = valid data, 0 = invalid data or n/a) | + * | 8 + i·12 | 21 + i·28 | `meas_y_valid` | uint8_t | - | Validity of `meas_y` (1 = valid data, 0 = invalid data or n/a) | + * | 9 + i·12 | 22 + i·28 | `meas_z_valid` | uint8_t | - | Validity of `meas_z` (1 = valid data, 0 = invalid data or n/a) | + * | 10 + i·12 | 23 + i·28 | `meas_type` | uint8_t | - | Type of measurement (see below) | + * | 11 + i·12 | 24 + i·28 | `meas_loc` | uint8_t | - | Location of measurement (see below) | + * | 12 + i·12 | 25 + i·28 | `reserved1` | uint8_t[4] | - | Reserved for future use. Set to 0. | + * | 13 + i·12 | 29 + i·28 | `timestamp_type` | uint8_t | - | Type of timestamp (see below) | + * | 14 + i·12 | 30 + i·28 | `gps_wno` | uint16_t | - | GPS week number | + * | 15 + i·12 | 32 + i·28 | `gps_tow` | uint32_t | * | GPS time of week [ms] or monotonic time [-] | + * + * Valid `meas_type` values are: + * + * | Value | Description | + * |:-----:|--------------------------| + * | `0` | Unspecified | + * | `1` | Velocity (wheel speed) | + * + * Valid `meas_loc` values are: + * + * | Value | Description | + * |:-----:|---------------------------------------------------| + * | `0` | Unspecified | + * | `1` | Measurement of a sensor at the rear-center (RC) | + * | `2` | Measurement of a sensor at the front-right (FR) | + * | `3` | Measurement of a sensor at the front-left (FL) | + * | `4` | Measurement of a sensor at the rear-right (RR) | + * | `5` | Measurement of a sensor at the rear-left (RL) | + * + * Valid `timestamp_type` values are: + * + * | Value | Description | + * |:-----:|-------------------------------------------------------------------------| + * | `0` | Unspecified | + * | `1` | Use time of arrival of the measurement (ignore `gps_wno` and `gps_tow`) | + * | `2` | Use monotonic time [any] (stored in the `gps_tow` field) | + * | `3` | Use GPS time (stored in `gps_wno` [-] and `gps_tow` [ms] fields) | + * + * @fp_msgspec_end + * + * @{ + */ +// clang-format on + +//! FP_B-MEASUREMENTS.version value +static constexpr uint8_t FP_B_MEASUREMENTS_V1 = 0x01; + +//! FP_B-MEASUREMENTS payload: head +struct FpbMeasurementsHead +{ + // clang-format off + uint8_t version = FP_B_MEASUREMENTS_V1; //!< Message version (= FP_B_MEASUREMENTS_V1 for this version of the message) + uint8_t num_meas = 0; //!< Number of measurements in the body (1..FP_B_MEASUREMENTS_MAX_NUM_MEAS) + uint8_t reserved0[6] = { 0 }; //!< Reserved for future use. Set to 0. + // clang-format on +}; + +//! FP_B-MEASUREMENTS payload head size +static constexpr std::size_t FP_B_MEASUREMENTS_HEAD_SIZE = 8; + +//! FP_B-MEASUREMENTS measurement type +enum class FpbMeasurementsMeasType : uint8_t // clang-format off +{ + UNSPECIFIED = 0, //!< Unspecified + VELOCITY = 1, //!< Velocity measuement (wheel speed) + // .... +}; // clang-format on + +//! FP_B-MEASUREMENTS measurement location +enum class FpbMeasurementsMeasLoc : uint8_t // clang-format off +{ + UNSPECIFIED = 0, //!< Unspecified + RC = 1, //!< Measurement of a sensor at the rear-center (RC) + FR = 2, //!< Measurement of a sensor at the front-right (FR) + FL = 3, //!< Measurement of a sensor at the front-left (FL) + RR = 4, //!< Measurement of a sensor at the rear-right (RR) + RL = 5, //!< Measurement of a sensor at the rear-left (RL) +}; // clang-format on + +//! FP_B-MEASUREMENTS timestamp type +enum class FpbMeasurementsTimestampType : uint8_t // clang-format off +{ + UNSPECIFIED = 0, //!< Unspecified + TIMEOFARRIVAL = 1, //!< Use time of arrival of the measurement (ignore gps_wno and gps_tow) + MONOTONIC = 2, //!< Use monotonic time [any] (stored in the gps_tow field) + GPS = 3, //!< Use GPS time (stored in gps_wno [-] and gps_tow [ms] fields) +}; // clang-format on + +//! FP_B-MEASUREMENTS payload: measurement +struct FpbMeasurementsMeas +{ + // clang-format off + int32_t meas_x = 0 ; //!< Measurement x + int32_t meas_y = 0 ; //!< Measurement y + int32_t meas_z = 0 ; //!< Measurement z + uint8_t meas_x_valid = 0; //!< Validity of measurement x (1 = meas_x contains valid data, 0 = data invalid or n/a) + uint8_t meas_y_valid = 0; //!< Validity of measurement y (1 = meas_x contains valid data, 0 = data invalid or n/a) + uint8_t meas_z_valid = 0; //!< Validity of measurement z (1 = meas_x contains valid data, 0 = data invalid or n/a) + uint8_t meas_type //! See #FpbMeasurementsMeasType + = types::EnumToVal(FpbMeasurementsMeasType::UNSPECIFIED); + uint8_t meas_loc //! See #FpbMeasurementsMeasLoc + = types::EnumToVal(FpbMeasurementsMeasLoc::UNSPECIFIED); + uint8_t reserved1[4] = { 0 }; //!< Reserved for future use. Set to 0. + uint8_t timestamp_type //! See #FpbMeasurementsTimestampType + = types::EnumToVal(FpbMeasurementsTimestampType::UNSPECIFIED); + uint16_t gps_wno = 0; //!< GPS week number [-] + uint32_t gps_tow = 0; //!< GPS time of week [ms] or monotonic time [-] + // clang-format on +}; + +//! Size of FpbMeasurementsMeas +static constexpr std::size_t FP_B_MEASUREMENTS_MEAS_SIZE = 28; + +//! Maximum number of measurements +static constexpr std::size_t FP_B_MEASUREMENTS_MAX_NUM_MEAS = 10; // Keep in sync with the docu above! + +static_assert(sizeof(FpbMeasurementsHead) == FP_B_MEASUREMENTS_HEAD_SIZE, ""); +static_assert(sizeof(FpbMeasurementsMeas) == FP_B_MEASUREMENTS_MEAS_SIZE, ""); + +///@} +// --------------------------------------------------------------------------------------------------------------------- +// clang-format off +/** + * @name FP_B-VERSION + * + * @fp_msgspec_begin{FP_B-VERSION} + * + * **Description:** + * + * This message contains version strings. + * + * **Payload fields:** + * + * | # | Offset | Field | Type | Unit | Description | + * |---:|--------:|-------------------|----------------|------|------------------------------------------------------| + * | 1 | 0 | `version` | uint8_t | - | Version of the FP_B_VERSION message (currently 1) | + * | 2 | 1 | `reserved0` | uint8_t[7] | - | Reserved for future use. Set to 0. | + * | 3 | 8 | `sw_version` | uint8_t[64] | - | Software version (nul-terminated string) | + * | 4 | 72 | `hw_name` | uint8_t[32] | - | Hardware name string (nul-terminated string) | + * | 5 | 104 | `hw_ver` | uint8_t[32] | - | Hardware version (nul-terminated string) | + * | 6 | 136 | `hw_uid` | uint8_t[32] | - | Hardware UID (nul-terminated string) | +* | 7 | 168 | `reserved1` | uint8_t[64] | - | Reserved for future use. Set to 0. | + * @fp_msgspec_end + * + * @{ + */ +// clang-format on + +//! FP_B-VERSION.version value +static constexpr uint8_t FP_B_VERSION_V1 = 0x01; + +//! FP_B-VERSION payload: head +struct FpbVersionPayload +{ // clang-format off + uint8_t version = FP_B_VERSION_V1; //!< Message version (= FP_B_VERSION_V1 for this version of the message) + uint8_t reserved0[7] = { 0 }; //!< Reserved for future use. Set to 0. + uint8_t sw_version[64] = { 0 }; //!< Software version (nul-terminated string) + uint8_t hw_name[32] = { 0 }; //!< Hardware name string (nul-terminated string) + uint8_t hw_ver[32] = { 0 }; //!< Hardware version (nul-terminated string) + uint8_t hw_uid[32] = { 0 }; //!< Hardware UID (nul-terminated string) + uint8_t reserved1[64] = { 0 }; //!< Reserved for future use. Set to 0. +}; // clang-format on + +//! Size of FpbVersionPayload +static constexpr std::size_t FP_B_VERSION_PAYLOAD_SIZE = 232; +static_assert(sizeof(FpbVersionPayload) == FP_B_VERSION_PAYLOAD_SIZE, ""); + +///@} + +/* ****************************************************************************************************************** */ +} // namespace fpb +} // namespace parser +} // namespace common +} // namespace fpsdk +#endif // __FPSDK_COMMON_PARSER_FPB_HPP__ diff --git a/fpsdk_common/include/fpsdk_common/parser/nmea.hpp b/fpsdk_common/include/fpsdk_common/parser/nmea.hpp new file mode 100644 index 0000000..0c525ad --- /dev/null +++ b/fpsdk_common/include/fpsdk_common/parser/nmea.hpp @@ -0,0 +1,695 @@ +/** + * \verbatim + * ___ ___ + * \ \ / / + * \ \/ / Copyright (c) Fixposition AG (www.fixposition.com) and contributors + * / /\ \ License: see the LICENSE file + * /__/ \__\ + * + * Based on work by flipflip (https://github.com/phkehl) + * The information on message structures, IDs, descriptions etc. in this file are from publicly available data, such as: + * - NMEA 0183 (https://www.nmea.org/) + * - https://en.wikipedia.org/wiki/NMEA_0183 + * - u-blox ZED-F9P Interface Description (HPG 1.50) (https://www.u-blox.com/en/docs/UBXDOC-963802114-12815), + * copyright (c) 2024 u-blox AG + * \endverbatim + * + * @file + * @brief Fixposition SDK: Parser NMEA routines and types + */ +// clang-format off +/** + * @page FPSDK_COMMON_PARSER_NMEA Parser NMEA routines and types + * + * **API**: fpsdk_common/parser/nmea.hpp and fpsdk::common::parser::nmea + * + * @fp_msgspec_begin{NMEA-Protocol} + * + * The NMEA framing and behaviour is defined by the NMEA 0183 standard (v4.11 and erratas). + * + * In NMEA speak messages are called *Sentences*. Frames (messages) are in this form: + * + * $TalkerFormatter,field1,field2,…,fieldN\*CC\\r\\n + * + * Where: + * + * - The NMEA style framing: + * - \$ + * -- Start character ("$", ASCII 36) + * - \*CC + * -- Checksum: "\*" (ASCII 42) and two digit XOR value of all payload + * characters in captial hexadecimal notation, for example: + * "FPX" = 'F' ^ 'P' ^ 'X' = 70 ^ 80 ^ 88 = 78 = 0x4e = checksum 4E + * - \\r\\n + * -- Sentence termination characters (CR + LF, ASCII 13 + 10) + * - A Talker ID -- Two capital characters: + * - `GP` -- Talker ID for GPS, also legacy resp. "compatibility" + * - `GL` -- Talker ID for GLONASS + * - `GA` -- Talker ID for Galileo + * - `GB` -- Talker ID for BeiDou + * - `GQ` -- Talker ID for QZSS + * - `GI` -- Talker ID for NavIC (IRNSS) + * - `GN` -- Talker ID for any combination of GNSS + * - A Formatter ID -- Three capital characters, for example: + * - `RMC` for the message containing recommended minimum specific GNSS data + * - See the NMEA 0183 standard document for an extensive list + * - Data fields (payload) + * - field1,field2,…,fieldN + * -- The structure of the message data is defined by the Formatter. + * Each field can contain all printable 7-bit ASCII characters (ASCII 32–126), excluding the + * reserved characters `!` (ASCII 33), `$` (ASCII 36), `*` (ASCII 42), `,` (ASCII 44), + * `\` (ASCII 92), `~` (ASCII 126). + * - Field separators + * - All fields (identifier, message type, message version, data fields) are separated by a `,` (comma, ASCII 44) + * - Null fields + * - Data fields can be _null_, meaning their value is absent to indicate that no data is + * available. The data for null fields is the empty string. For example: + * - Definition: …,fieldi,fieldi+1,fieldi+2,… + * - Values: fieldi = 123, fieldi+1 = _null_, + * fieldi+2 = 456 + * - Payload string: …,123,,456,… + * - Data field types: + * - See the NMEA 0183 standard document for specifications + * + * @fp_msgspec_end + * + */ +// clang-format on +#ifndef __FPSDK_COMMON_PARSER_NMEA_HPP__ +#define __FPSDK_COMMON_PARSER_NMEA_HPP__ + +/* LIBC/STL */ +#include +#include +#include +#include + +/* EXTERNAL */ + +/* PACKAGE */ + +namespace fpsdk { +namespace common { +namespace parser { +/** + * @brief Parser NMEA routines and types + */ +namespace nmea { +/* ****************************************************************************************************************** */ + +static constexpr uint8_t NMEA_PREAMBLE = '$'; //!< NMEA framing preamble +static constexpr std::size_t NMEA_FRAME_SIZE = 6; //!< NMEA frame size ("$*cc\r\n") + +//! NMEA message meta data +struct NmeaMessageMeta +{ + char talker_[3] = { 0 }; //!< Talker ID (for example, "GP", "GN" or "P"), nul-terminated string + char formatter_[20] = { 0 }; //!< Formatter (for example, "GGA", "RMC", or "UBX"), nul-terminated string + int payload_ix0_ = 0; //!< Index (offset) for start of payload, 0 if no payload available + int payload_ix1_ = 0; //!< Index (offset) for end of payload, 0 if no payload available +}; + +/** + * @brief Get NMEA message meta data + * + * @param[out] meta The meta data + * @param[in] msg Pointer to the NMEA message + * @param[in] msg_size Size of the NMEA message (>= 11) + * + * @note No check on the data provided is done. The caller must ensure that the data is a correct NMEA message. + * + * @returns true if the meta data was successfully extracted, false otherwise + */ +bool NmeaGetMessageMeta(NmeaMessageMeta& meta, const uint8_t* msg, const std::size_t msg_size); + +/** + * @brief Get NMEA message name + * + * Generates a name (string) in the form "NMEA-TALKER-FORMATTER" (for example, "NMEA-GP-GGA"). Some proprietary messages + * are recognised, for example, "NMEA-PUBX-POSITION". + * + * @param[out] name String to write the name to + * @param[in] size Size of \c name (incl. nul termination) + * @param[in] msg Pointer to the NMEA message + * @param[in] msg_size Size of the \c msg + * + * @note No check on the data provided is done. The caller must ensure that the data is a valid NMEA message. + * + * @returns true if message name was generated, false if \c name buffer was too small + */ +bool NmeaGetMessageName(char* name, const std::size_t size, const uint8_t* msg, const std::size_t msg_size); + +/** + * @brief Get NMEA message info + * + * This stringifies the content of some NMEA messages, for debugging. + * + * @param[out] info String to write the info to + * @param[in] size Size of \c name (incl. nul termination) + * @param[in] msg Pointer to the NMEA message + * @param[in] msg_size Size of the \c msg + * + * @note No check on the data provided is done. The caller must ensure that the data is a valid NMEA message. + * + * @returns true if message info was generated (even if info is empty), false if \c name buffer was too small + */ +bool NmeaGetMessageInfo(char* info, const std::size_t size, const uint8_t* msg, const std::size_t msg_size); + +/** + * @brief NMEA coordinates (integer degrees, float minutes and a sign for N/S resp. E/W) + */ +struct NmeaCoordinates +{ + /** + * @brief Constructor + * + * @param[in] degs Decimal degrees + * @param[in] digits Number of digits (0-12), param clamped to range + */ + NmeaCoordinates(const double degs, const int digits = 5); + + int deg_; //!< Integer degrees value, >= 0 + double min_; //!< Fractional minutes value, >= 0.0 + bool sign_; //!< false for negative (S or W), true for positive (N or E) +}; + +// --------------------------------------------------------------------------------------------------------------------- + +/** + * @brief NMEA talker IDs + * + * @note Do not use <, >, >=, <= operators on this! + */ +enum class NmeaTalkerId : int +{ // clang-format off + UNSPECIFIED = '?', //!< Unspecified + PROPRIETARY = 'x', //!< Proprietary + GPS_SBAS = 'P', //!< GPS and/or SBAS + GLO = 'L', //!< GLONASS + GAL = 'A', //!< GALILEO + BDS = 'B', //!< BeiDou + NAVIC = 'I', //!< NavIC + QZSS = 'Q', //!< QZSS + GNSS = 'N', //!< GNSS (multi-constellation) +}; // clang-format on + +/** + * @brief NMEA-Gx-GGA quality indicator + * + * @note Do not use <, >, >=, <= operators on this! + */ +enum class NmeaQualityGga : int +{ // clang-format off + UNSPECIFIED = '?', //!< Unspecified + NOFIX = '0', //!< No fix + SPP = '1', //!< Autonomous GNSS fix + DGNSS = '2', //!< Differential GPS fix (e.g. with SBAS) + PPS = '3', //!< PPS mode + RTK_FIXED = '4', //!< RTK fixed + RTK_FLOAT = '5', //!< RTK float + ESTIMATED = '6', //!< Estimated (dead reckoning only) + MANUAL = '7', //!< Manual input mode + SIM = '8', //!< Simulator +}; // clang-format on + +/** + * @brief NMEA-Gx-GLL and NMEA-Gx-RMC status + * + * @note Do not use <, >, >=, <= operators on this! + */ +enum class NmeaStatusGllRmc : int +{ // clang-format off + UNSPECIFIED = '?', //!< Unspecified + INVALID = 'V', //!< Data invalid + VALID = 'A', //!< Data valid + // DIFFERENTIAL = 'D', // @todo another possible value? +}; // clang-format on + +/** + * @brief NMEA-Gx-GLL and NMEA-Gx-VTG pos mode + * + * @note Do not use <, >, >=, <= operators on this! + */ +enum class NmeaModeGllVtg : int +{ // clang-format off + UNSPECIFIED = '?', //!< Unspecified + INVALID = 'N', //!< Invalid (no fix) + AUTONOMOUS = 'A', //!< Autonomous mode (SPP) + DGNSS = 'D', //!< Differential GNSS fix + ESTIMATED = 'E', //!< Estimated (dead reckoning only) + MANUAL = 'M', //!< Manual input mode + SIM = 'S', //!< Simulator mode +}; // clang-format on + +/** + * @brief NMEA-Gx-RMC and NMEA-Gx-GNS pos mode + * + * @note Do not use <, >, >=, <= operators on this! + */ +enum class NmeaModeRmcGns : int +{ // clang-format off + UNSPECIFIED = '?', //!< Unspecified + INVALID = 'N', //!< Invalid (no fix) + AUTONOMOUS = 'A', //!< Autonomous mode (SPP) + DGNSS = 'D', //!< Differential GNSS fix + ESTIMATED = 'E', //!< Estimated (dead reckoning only) + RTK_FIXED = 'R', //!< RTK fixed + RTK_FLOAT = 'F', //!< RTK float + PRECISE = 'P', //!< Precise + MANUAL = 'M', //!< Manual input mode + SIM = 'S', //!< Simulator mode +}; // clang-format on + +/** + * @brief NMEA-Gx-RMC navigational status + * + * @note Do not use <, >, >=, <= operators on this! + */ +enum class NmeaNavStatusRmc : int +{ // clang-format off + UNSPECIFIED = '?', //!< Unspecified + SAFE = 'S', //!< Safe + CAUTION = 'C', //!< Caution + UNSAFE = 'U', //!< Unsafe + NA = 'V', //!< Equipment does not provide navigational status +}; // clang-format on + +/** + * @brief NMEA-Gx-GNS operation mode + * + * @note Do not use <, >, >=, <= operators on this! + */ +enum class NmeaOpModeGsa : int +{ // clang-format off + UNSPECIFIED = '?', //!< Unspecified + MANUAL = 'M', //!< Manual + AUTO = 'A', //!< Automatic +}; // clang-format on + +/** + * @brief NMEA-Gx-GNS nav mode + * + * @note Do not use <, >, >=, <= operators on this! + */ +enum class NmeaNavModeGsa : int +{ // clang-format off + UNSPECIFIED = '?', //!< Unspecified + NOFIX = '1', //!< No fix + FIX2D = '2', //!< 2D fix + FIX3D = '3', //!< 3D fix +}; // clang-format on + +/** + * @brief NMEA system IDs + */ +enum class NmeaSystemId : int +{ // clang-format off + UNSPECIFIED = '?', //!< Unspecified + GPS_SBAS = '1', //!< GPS and/or SBAS + GLO = '2', //!< GLONASS + GAL = '3', //!< Galileo + BDS = '4', //!< BeiDou + QZSS = '5', //!< QZSS + NAVIC = '6', //!< NavIC +}; // clang-format on + +/** + * @brief NMEA signal IDs + */ +enum class NmeaSignalId : int +{ // clang-format off + UNSPECIFIED = '?', //!< Unspecified + GPS_L1CA = '1', //!< GPS L1 C/A + GPS_L2CL = '6', //!< GPS L2 CL + GPS_L2CM = '5', //!< GPS L2 CM + GPS_L5I = '7', //!< GPS L5 I + GPS_L5Q = '8', //!< GPS L5 Q + SBAS_L1CA = '1', //!< SBAS L1 C/A + GAL_E1 = '7', //!< Galileo E1 + GAL_E5A = '1', //!< Galileo E5 A + GAL_E5B = '2', //!< Galileo E5 B + BDS_B1ID = '1', //!< BeiDou B1I D + BDS_B2ID = 'B', //!< BeiDou B2I D + BDS_B1C = '3', //!< BeiDou B1 C + BDS_B2A = '5', //!< BeiDou B2 a + QZSS_L1CA = '1', //!< QZSS L1 C/A + QZSS_L1S = '4', //!< QZSS L1S + QZSS_L2CM = '5', //!< QZSS L2 CM + QZSS_L2CL = '6', //!< QZSS L2 CL + QZSS_L5I = '7', //!< QZSS L5 I + QZSS_L5Q = '8', //!< QZSS L5 Q + GLO_L1OF = '1', //!< GLONASS L1 OF + GLO_L2OF = '3', //!< GLONASS L2 OF + NAVIC_L5A = '5', //!< NavIC L5 A +}; // clang-format on + +/** + * @brief NMEA time (hour, minutes, seconds) + */ +struct NmeaTime +{ + bool valid = false; //!< Data is valid + int hours = 0; //!< Hours + int mins = 0; //!< Minutes + double secs = 0.0; //!< Seconds + + bool operator==(const NmeaTime& rhs) const; //!< Equal + bool operator!=(const NmeaTime& rhs) const; //!< Not equal +}; + +/** + * @brief NMEA date (year, month, day) + */ +struct NmeaDate +{ + bool valid = false; //!< Data is valid + int years = 0; //!< Year + int months = 0; //!< Month + int days = 0.0; //!< Day + + bool operator==(const NmeaDate& rhs) const; //!< Equal + bool operator!=(const NmeaDate& rhs) const; //!< Not equal +}; + +/** + * @brief NMEA geodetic position + */ +struct NmeaLlh +{ + bool latlon_valid = false; //!< Latitude/longitude is valid + double lat = 0.0; //!< Latitude [deg], >= 0.0 East, < 0.0 West + double lon = 0.0; //!< Longitude [deg], >= 0.0 North, < 0.0 South + bool height_valid = false; //!< Height is valid + double height = 0.0; //!< Ellipsoidal (!) height [m] +}; + +/** + * @brief NMEA satellite (used, e.g. in GSA) + */ +struct NmeaSat +{ + bool valid = false; //!< Data is valid + NmeaSystemId system = NmeaSystemId::UNSPECIFIED; //!< System ID + int svid = 0; //!< Satellite ID (numbering cf. NMEA 0183) +}; + +/** + * @brief Constants for different versions of NMEA + */ +struct NmeaVersion +{ + const int svid_min_gps; //!< Min GPS satellite ID + const int svid_max_gps; //!< Max GPS satellite ID + const int svid_min_sbs; //!< Min SBAS satellite ID + const int svid_max_sbs; //!< Max SBAS satellite ID + const int svid_min_glo; //!< Min GLONASS satellite ID + const int svid_max_glo; //!< Max GLONASS satellite ID + const int svid_min_gal; //!< Min Galileo satellite ID + const int svid_max_gal; //!< Max Galileo satellite ID + const int svid_min_bds; //!< Min BeiDou satellite ID + const int svid_max_bds; //!< Max BeiDou satellite ID + const int svid_min_qzs; //!< Min QZSS satellite ID + const int svid_max_qzs; //!< Max QZSS satellite ID + + static const NmeaVersion V410; //!< Values for NMEA v4.10 + static const NmeaVersion V410_UBX_EXT; //!< Values for NMEA v4.10 extended (u-blox flavour) + static const NmeaVersion V411; //!< Values for NMEA v4.11 +}; + +/** + * NMEA satellite position (GSA) + */ +struct NmeaAzEl +{ + bool valid = false; //!< Data is valid + NmeaSystemId system = NmeaSystemId::UNSPECIFIED; //!< System ID + int svid = 0; //!< Satellite ID (numbering cf. NMEA 0183) + int el = 0; //!< Elevation [deg] (-90..90) + int az = 0; //!< Azimuth [deg] (0..360) +}; + +/** + * NMEA signal levels (GSA) + */ +struct NmeaCno +{ + bool valid = false; //!< Data valid + NmeaSystemId system = NmeaSystemId::UNSPECIFIED; //!< System ID + int svid = 0; //!< Satellite ID (numbering cf. NMEA 0183) + NmeaSignalId signal = NmeaSignalId::UNSPECIFIED; //!< Signal ID + int cno = 0; //!< Signal level [dBHz] +}; + +/** + * @brief NMEA integer value + */ +struct NmeaInt +{ + bool valid = false; //!< Data is valid + int value = 0; //!< Value +}; + +/** + * @brief NMEA float value + */ +struct NmeaFloat +{ + bool valid = false; //!< Data is valid + double value = 0; //!< Value +}; + +/** + * @brief NMEA-Gx-GGA message payload + */ +struct NmeaGgaPayload +{ + NmeaTalkerId talker = NmeaTalkerId::UNSPECIFIED; //!< Talker + NmeaTime time; //!< Time + NmeaLlh llh; //!< Position + NmeaQualityGga quality = NmeaQualityGga::UNSPECIFIED; //!< Fix quality + NmeaInt num_sv; //!< Number of satellites used (may be limited to 12) + NmeaFloat hdop; //!< Horizontal dilution of precision (only with valid fix) + NmeaFloat diff_age; //!< Differential data age (optional, NMEA 4.11 only) + NmeaInt diff_sta; //!< Differential station ID (optional, NMEA 4.11 only) + + /** + * @brief Set data from sentence + * + * @param[in] msg Pointer to the NMEA message + * @param[in] msg_size Size of the NMEA message (>= 11) + * + * @returns true if sentence payload was correct and all data could be extracted (fields are now valid), or false + * otherwise (fields are now invalid) + */ + bool SetFromMsg(const uint8_t* msg, const std::size_t msg_size); +}; + +/** + * @brief NMEA-Gx-GLL message payload + */ +struct NmeaGllPayload +{ + NmeaTalkerId talker = NmeaTalkerId::UNSPECIFIED; //!< Talker + NmeaLlh llh; //!< Position + NmeaTime time; //!< Time + NmeaStatusGllRmc status = NmeaStatusGllRmc::UNSPECIFIED; //!< Positioning system status + NmeaModeGllVtg mode = NmeaModeGllVtg::UNSPECIFIED; //!< Positioning system mode + + /** + * @brief Set data from sentence + * + * @param[in] msg Pointer to the NMEA message + * @param[in] msg_size Size of the NMEA message (>= 11) + * + * @returns true if sentence payload was correct and all data could be extracted (fields are now valid), or false + * otherwise (fields are now invalid) + */ + bool SetFromMsg(const uint8_t* msg, const std::size_t msg_size); +}; + +/** + * @brief NMEA-Gx-RMC message payload + */ +struct NmeaRmcPayload +{ + NmeaTalkerId talker = NmeaTalkerId::UNSPECIFIED; //!< Talker + NmeaTime time; //!< Time + NmeaStatusGllRmc status = NmeaStatusGllRmc::UNSPECIFIED; //!< Positioning system status + NmeaLlh llh; //!< Position + NmeaFloat speed; //!< Speed over ground [knots] + NmeaFloat course; //!< Course over ground w.r.t. True North [deg] + NmeaDate date; //!< Date + NmeaModeRmcGns mode = NmeaModeRmcGns::UNSPECIFIED; //!< positioning system mode indicator + NmeaNavStatusRmc navstatus = NmeaNavStatusRmc::UNSPECIFIED; //!< Navigational status + /** + * @brief Set data from sentence + * + * @param[in] msg Pointer to the NMEA message + * @param[in] msg_size Size of the NMEA message (>= 11) + * + * @returns true if sentence payload was correct and all data could be extracted (fields are now valid), or false + * otherwise (fields are now invalid) + */ + bool SetFromMsg(const uint8_t* msg, const std::size_t msg_size); +}; + +/** + * @brief NMEA-Gx-VTG message payload + */ +struct NmeaVtgPayload +{ + NmeaTalkerId talker = NmeaTalkerId::UNSPECIFIED; //!< Talker + NmeaFloat cogt; //!< Course over ground (true) [deg] + NmeaFloat sogn; //!< Speed over ground [knots] + NmeaFloat sogk; //!< Speed over ground [km/h] + NmeaModeGllVtg mode; //!< Positioning system mode + + /** + * @brief Set data from sentence + * + * @param[in] msg Pointer to the NMEA message + * @param[in] msg_size Size of the NMEA message (>= 11) + * + * @returns true if sentence payload was correct and all data could be extracted (fields are now valid), or false + * otherwise (fields are now invalid) + */ + bool SetFromMsg(const uint8_t* msg, const std::size_t msg_size); +}; + +/** + * @brief NMEA-Gx-GSA message payload (NMEA 4.11 only!) + */ +struct NmeaGsaPayload +{ + NmeaTalkerId talker = NmeaTalkerId::UNSPECIFIED; //!< Talker + NmeaOpModeGsa opmode = NmeaOpModeGsa::UNSPECIFIED; //!< Operation mode + NmeaNavModeGsa navmode = NmeaNavModeGsa::UNSPECIFIED; //!< Nav mode + std::array sats; //!< Satellites, valid ones are 0..(num_sats-1) + int num_sats = 0; //!< Number of valid sats (the first n of sats[]) + NmeaFloat pdop; //!< PDOP + NmeaFloat hdop; //!< HDOP + NmeaFloat vdop; //!< VDOP + NmeaSystemId system = NmeaSystemId::UNSPECIFIED; //!< System ID + + /** + * @brief Set data from sentence + * + * @param[in] msg Pointer to the NMEA message + * @param[in] msg_size Size of the NMEA message (>= 11) + * + * @returns true if sentence payload was correct and all data could be extracted (fields are now valid), or false + * otherwise (fields are now invalid) + */ + bool SetFromMsg(const uint8_t* msg, const std::size_t msg_size); +}; + +/** + * @brief NMEA-Gx-GSV message payload (NMEA 4.11 only!) + */ +struct NmeaGsvPayload +{ + NmeaTalkerId talker = NmeaTalkerId::UNSPECIFIED; //!< Talker + NmeaInt num_msgs; //!< Number of messages in this GSV sequence (for this signal ID) + NmeaInt msg_num; //!< Message number in sequence (1...num_msgs) + NmeaInt tot_num_sat; //!< Number of sat/sig info in the whole sequence of GSV messages + std::array azels; //!< Satellite positions, valid ones are 0..(num_sats-1) + int num_azels = 0; //!< Number of valid satellite positions (the first n of azels[]) + std::array cnos; //!< Signal levels, valid ones are 0..(num_sats-1) + int num_cnos = 0; //!< Number of valid signal levels (the first n of azels[]) + NmeaSystemId system; //!< System ID + NmeaSignalId signal; //!< Signal ID + + /** + * @brief Set data from sentence + * + * @param[in] msg Pointer to the NMEA message + * @param[in] msg_size Size of the NMEA message (>= 11) + * + * @returns true if sentence payload was correct and all data could be extracted (fields are now valid), or false + * otherwise (fields are now invalid) + */ + bool SetFromMsg(const uint8_t* msg, const std::size_t msg_size); +}; + +// --------------------------------------------------------------------------------------------------------------------- + +/** + * @brief Collector for NMEA-Gx-GSA and NMEA-Gx-GPA + */ +struct NmeaCollectGsaGsv +{ + /** + * @brief Satellite info + */ + struct Sat + { + NmeaSystemId system_ = NmeaSystemId::UNSPECIFIED; //!< System ID + int svid_ = 0; //!< Satellite ID (numbering cf. NMEA 0183) + int az_ = 0; //!< Azimuth [deg] (0..360) + int el_ = 0; //!< Elevation [deg] (-90..90) + }; + + /** + * Signal info + */ + struct Sig + { + NmeaSystemId system_ = NmeaSystemId::UNSPECIFIED; //!< System ID + int svid_ = 0; //!< Satellite ID (numbering cf. NMEA 0183) + NmeaSignalId signal_ = NmeaSignalId::UNSPECIFIED; //!< Signal ID + double cno_ = 0.0; //!< Signal level [dBHz] + bool used_ = false; //!< Signal is used in navigation + }; + + std::vector sats_; //!< Collected satellite info + std::vector sigs_; //!< Collected signal info + + /** + * @brief Add NMEA-GN-GSA message to collection + * + * These must be provided in order and completely, and before the GSV messages. + * + * @param[in] gsa Decoded message payload + * + * @returns true if the message was accepted, false otherwise + */ + bool AddGsa(const NmeaGsaPayload& gsa); + + /** + * @brief Add NMEA-Gx-GSV message to collection + * + * These must be provided in order and completely, and after the GSA messages. + * + * @param[in] gsv Decoded message payload + * + * @returns true if the message was accepted, false otherwise + */ + bool AddGsv(const NmeaGsvPayload& gsv); + + /** + * @brief Complete collection after feeding all GSA and GSV messages + */ + void Complete(); + + /** + * @brief Add NMEA-GN-GSA and NMEA-Gx-GSV messages to collection + * + * Does all of AddGsa(), AddGsv() and Complete() in one call. + * + * @param[in] gsas All decoded message payloads, complete and in order + * @param[in] gsvs All decoded message payloads, complete and in order + * + * @returns true if all messages were collected successfully + */ + bool AddGsaAndGsv(const std::vector& gsas, const std::vector& gsvs); + + private: + std::vector gsa_sats_; //!< Satellites used +}; + +/* ****************************************************************************************************************** */ +} // namespace nmea +} // namespace parser +} // namespace common +} // namespace fpsdk +#endif // __FPSDK_COMMON_PARSER_NMEA_HPP__ diff --git a/fpsdk_common/include/fpsdk_common/parser/novb.hpp b/fpsdk_common/include/fpsdk_common/parser/novb.hpp new file mode 100644 index 0000000..ae1add3 --- /dev/null +++ b/fpsdk_common/include/fpsdk_common/parser/novb.hpp @@ -0,0 +1,661 @@ +/** + * \verbatim + * ___ ___ + * \ \ / / + * \ \/ / Copyright (c) Fixposition AG (www.fixposition.com) and contributors + * / /\ \ License: see the LICENSE file + * /__/ \__\ + * + * Parts copyright (c) 2020 NovAtel Inc. See the LICENSE file. + * Based on work by flipflip (https://github.com/phkehl) + * The information on message structures, IDs, descriptions etc. in this file are from publicly available data, such as: + * - https://github.com/novatel/novatel_oem7_driver/tree/master + * - https://docs.novatel.com/OEM7/Content/Messages/Binary.htm + * - https://docs.novatel.com/OEM7/Content/Messages/Description_of_Short_Headers.htm + * \endverbatim + * + * @file + * @brief Fixposition SDK: Parser NOV_B routines and types + * + * @page FPSDK_COMMON_PARSER_NOVB Parser NOV_B routines and types + * + * **API**: fpsdk_common/parser/novb.hpp and fpsdk::common::parser::novb + * + */ +#ifndef __FPSDK_COMMON_PARSER_NOVB_HPP__ +#define __FPSDK_COMMON_PARSER_NOVB_HPP__ + +/* LIBC/STL */ +#include + +/* EXTERNAL */ + +/* PACKAGE */ + +namespace fpsdk { +namespace common { +namespace parser { +/** + * @brief Parser NOV_B routines and types + */ +namespace novb { +/* ****************************************************************************************************************** */ + +// Doxygen is easily confused.. :-/ +//! Message truct that must be packed +#ifndef _DOXYGEN_ +# define NOV_B_PACKED __attribute__((packed)) +#else +# define NOV_B_PACKED /* packed */ +#endif + +static constexpr uint8_t NOV_B_SYNC_1 = 0xaa; //!< Sync char 1 +static constexpr uint8_t NOV_B_SYNC_2 = 0x44; //!< Sync char 2 +static constexpr uint8_t NOV_B_SYNC_3_LONG = 0x12; //!< Sync char 3 (long header) +static constexpr uint8_t NOV_B_SYNC_3_SHORT = 0x13; //!< Sync char 3 (short header) +static constexpr std::size_t NOV_B_HEAD_SIZE_LONG = 28; //!< Size of the NOV_B long header (NovbLongHeader) +static constexpr std::size_t NOV_B_HEAD_SIZE_SHORT = 12; //!< Size of the NOV_B short header (NovbShortHeader) + +/** + * @brief Get message ID + * + * @param[in] msg Pointer to the start of the message + * + * @note No check on the data provided is done. The caller must ensure that the data is a valid NOV_B message. + * + * @returns message ID + */ +constexpr uint16_t NovbMsgId(const uint8_t* msg) +{ + return (((uint16_t)((uint8_t*)msg)[5] << 8) | (uint16_t)((uint8_t*)msg)[4]); +} + +/** + * @brief Check if message has the long header + * + * @param[in] msg Pointer to the start of the message + * + * @note No check on the data provided is done. The caller must ensure that the data is a valid NOV_B message. + * + * @returns true if the message has the long header (NovbLongHeader) + */ +constexpr bool NovbIsLongHeader(const uint8_t* msg) +{ + return msg[2] == NOV_B_SYNC_3_LONG; +} + +/** + * @brief Check if message has the short header + * + * @param[in] msg Pointer to the start of the message + * + * @note No check on the data provided is done. The caller must ensure that the data is a valid NOV_B message. + * + * @returns true if the message has the short header (NovbShortHeader) + */ +constexpr bool NovbIsShortHeader(const uint8_t* msg) +{ + return msg[2] == NOV_B_SYNC_3_SHORT; +} + +/** + * @brief Get NOV_B message name + * + * Generates a name (string) in the form "NOV_B-NAME", where NAME is a suitable stringifications of the + * message ID if known (for example, "NOV_B-BESTGNSSPOS", respectively "%05u" formatted message ID if unknown (for + * example, "NOV_B-MSG01234"). + * + * @param[out] name String to write the name to + * @param[in] size Size of \c name (incl. nul termination) + * @param[in] msg Pointer to the NOV_B message + * @param[in] msg_size Size of the \c msg + * + * @note No check on the data provided is done. The caller must ensure that the data is a valid NOV_B message. + * + * @returns true if message name was generated, false if \c name buffer was too small + */ +bool NovbGetMessageName(char* name, const std::size_t size, const uint8_t* msg, const std::size_t msg_size); + +/** + * @brief Get NOV_B message info + * + * This stringifies the content of some NOV_B messages, for debugging. + * + * @param[out] info String to write the info to + * @param[in] size Size of \c name (incl. nul termination) + * @param[in] msg Pointer to the NOV_B message + * @param[in] msg_size Size of the \c msg + * + * @note No check on the data provided is done. The caller must ensure that the data is a valid NOV_B message. + * + * @returns true if message info was generated (even if info is empty), false if \c name buffer was too small + */ +bool NovbGetMessageInfo(char* info, const std::size_t size, const uint8_t* msg, const std::size_t msg_size); + +/** + * @name NOV_B messages (names and IDs) + * + * @{ + */ +// clang-format off +// @fp_codegen_begin{FPSDK_COMMON_PARSER_NOVB_MESSAGES} +static constexpr uint16_t NOV_B_BESTGNSSPOS_MSGID = 1429; //!< NOV_B-BESTGNSSPOS message ID +static constexpr const char* NOV_B_BESTGNSSPOS_STRID = "NOV_B-BESTGNSSPOS"; //!< NOV_B-BESTGNSSPOS message name +static constexpr uint16_t NOV_B_BESTPOS_MSGID = 42; //!< NOV_B-BESTPOS message ID +static constexpr const char* NOV_B_BESTPOS_STRID = "NOV_B-BESTPOS"; //!< NOV_B-BESTPOS message name +static constexpr uint16_t NOV_B_BESTUTM_MSGID = 726; //!< NOV_B-BESTUTM message ID +static constexpr const char* NOV_B_BESTUTM_STRID = "NOV_B-BESTUTM"; //!< NOV_B-BESTUTM message name +static constexpr uint16_t NOV_B_BESTVEL_MSGID = 99; //!< NOV_B-BESTVEL message ID +static constexpr const char* NOV_B_BESTVEL_STRID = "NOV_B-BESTVEL"; //!< NOV_B-BESTVEL message name +static constexpr uint16_t NOV_B_BESTXYZ_MSGID = 241; //!< NOV_B-BESTXYZ message ID +static constexpr const char* NOV_B_BESTXYZ_STRID = "NOV_B-BESTXYZ"; //!< NOV_B-BESTXYZ message name +static constexpr uint16_t NOV_B_CORRIMUS_MSGID = 2264; //!< NOV_B-CORRIMUS message ID +static constexpr const char* NOV_B_CORRIMUS_STRID = "NOV_B-CORRIMUS"; //!< NOV_B-CORRIMUS message name +static constexpr uint16_t NOV_B_HEADING2_MSGID = 1335; //!< NOV_B-HEADING2 message ID +static constexpr const char* NOV_B_HEADING2_STRID = "NOV_B-HEADING2"; //!< NOV_B-HEADING2 message name +static constexpr uint16_t NOV_B_IMURATECORRIMUS_MSGID = 1362; //!< NOV_B-IMURATECORRIMUS message ID +static constexpr const char* NOV_B_IMURATECORRIMUS_STRID = "NOV_B-IMURATECORRIMUS"; //!< NOV_B-IMURATECORRIMUS message name +static constexpr uint16_t NOV_B_INSCONFIG_MSGID = 1945; //!< NOV_B-INSCONFIG message ID +static constexpr const char* NOV_B_INSCONFIG_STRID = "NOV_B-INSCONFIG"; //!< NOV_B-INSCONFIG message name +static constexpr uint16_t NOV_B_INSPVA_MSGID = 507; //!< NOV_B-INSPVA message ID +static constexpr const char* NOV_B_INSPVA_STRID = "NOV_B-INSPVA"; //!< NOV_B-INSPVA message name +static constexpr uint16_t NOV_B_INSPVAS_MSGID = 508; //!< NOV_B-INSPVAS message ID +static constexpr const char* NOV_B_INSPVAS_STRID = "NOV_B-INSPVAS"; //!< NOV_B-INSPVAS message name +static constexpr uint16_t NOV_B_INSPVAX_MSGID = 1465; //!< NOV_B-INSPVAX message ID +static constexpr const char* NOV_B_INSPVAX_STRID = "NOV_B-INSPVAX"; //!< NOV_B-INSPVAX message name +static constexpr uint16_t NOV_B_INSSTDEV_MSGID = 2051; //!< NOV_B-INSSTDEV message ID +static constexpr const char* NOV_B_INSSTDEV_STRID = "NOV_B-INSSTDEV"; //!< NOV_B-INSSTDEV message name +static constexpr uint16_t NOV_B_PSRDOP2_MSGID = 1163; //!< NOV_B-PSRDOP2 message ID +static constexpr const char* NOV_B_PSRDOP2_STRID = "NOV_B-PSRDOP2"; //!< NOV_B-PSRDOP2 message name +static constexpr uint16_t NOV_B_RAWDMI_MSGID = 2269; //!< NOV_B-RAWDMI message ID +static constexpr const char* NOV_B_RAWDMI_STRID = "NOV_B-RAWDMI"; //!< NOV_B-RAWDMI message name +static constexpr uint16_t NOV_B_RAWIMU_MSGID = 268; //!< NOV_B-RAWIMU message ID +static constexpr const char* NOV_B_RAWIMU_STRID = "NOV_B-RAWIMU"; //!< NOV_B-RAWIMU message name +static constexpr uint16_t NOV_B_RAWIMUSX_MSGID = 1462; //!< NOV_B-RAWIMUSX message ID +static constexpr const char* NOV_B_RAWIMUSX_STRID = "NOV_B-RAWIMUSX"; //!< NOV_B-RAWIMUSX message name +static constexpr uint16_t NOV_B_RXSTATUS_MSGID = 93; //!< NOV_B-RXSTATUS message ID +static constexpr const char* NOV_B_RXSTATUS_STRID = "NOV_B-RXSTATUS"; //!< NOV_B-RXSTATUS message name +static constexpr uint16_t NOV_B_TIME_MSGID = 101; //!< NOV_B-TIME message ID +static constexpr const char* NOV_B_TIME_STRID = "NOV_B-TIME"; //!< NOV_B-TIME message name +// @fp_codegen_end{FPSDK_COMMON_PARSER_NOVB_MESSAGES} +// clang-format on +///@} + +// --------------------------------------------------------------------------------------------------------------------- + +/** + * @brief NOV_B frame long header + * + * See https://docs.novatel.com/OEM7/Content/Messages/Binary.htm + */ +struct NovbLongHeader +{ // clang-format off + uint8_t sync1; //!< = NOV_B_SYNC_1 + uint8_t sync2; //!< = NOV_B_SYNC_2 + uint8_t sync3; //!< = NOV_B_SYNC_3_LONG + uint8_t header_length; //!< sizeof(NovbLongHeader) + uint16_t message_id; //!< Message ID + uint8_t message_type; //!< Message type (see NovbMsgTypeSource) + uint8_t port_address; //!< Port address (see NovbPortAddr) + uint16_t message_length; //!< Message (payload) length + uint16_t sequence; //!< Sequence for groups of same messages + uint8_t idle_time; //!< CPU idle [%] + uint8_t time_status; //!< Time quality indicator (see NovbTimeStatus) + uint16_t gps_week; //!< GPS week number + int32_t gps_milliseconds; //!< GPS time of week [ms] + uint32_t receiver_status; //!< Receiver status flags + uint16_t reserved; //!< Reserved + uint16_t receiver_version; //!< Receiver sw version +}; // clang-format on + +static_assert(sizeof(NovbLongHeader) == NOV_B_HEAD_SIZE_LONG, ""); + +/** + * @brief NOV_B frame short header + * + * See https://docs.novatel.com/OEM7/Content/Messages/Description_of_Short_Headers.htm + */ +struct NovbShortHeader +{ // clang-format off + uint8_t sync1; //!< = NOV_B_SYNC_1 + uint8_t sync2; //!< = NOV_B_SYNC_2 + uint8_t sync3; //!< = NOV_B_SYNC_3_LONG + uint8_t message_length; //!< Message (payload) length + uint16_t message_id; //!< Message ID + uint16_t gps_week; //!< GPS week number + int32_t gps_milliseconds; //!< GPS time of week [ms] +}; // clang-format on + +static_assert(sizeof(NovbShortHeader) == NOV_B_HEAD_SIZE_SHORT, ""); + +/** + * @brief Message type measurement source (bits 4..0 of NovbLongHeader.message_type) + */ +enum class NovbMsgTypeSource : uint8_t +{ // clang-format off + PRIMARY = 0b00000000, //!< Primary antenna + SECONDARY = 0b00000001, //!< Secondary antenna + _MASK = 0b00011111, //!< Mask for the source part of the NovbLongHeader.message_type field +}; // clang-format on + +/** + * @brief Stringify message type measurement source + * + * @param[in] message_type Message type + * + * @returns a unique string for the message type measurement source + */ +const char* NovbMsgTypeSourceStr(const uint8_t message_type); + +/** + * @brief Message type format (bits 6..5 of NovbLongHeader.message_type) + */ +enum class NovbMsgTypeFormat : uint8_t +{ // clang-format off + BINARY = 0b00000000, //!< Binary + ASCII = 0b00100000, //!< ASCII + AASCII_NMEA = 0b01000000, //!< Abbreviated ASCII, NMEA + RESERVED = 0b01100000, //!< Reserved + _MASK = 0b01100000, //!< Mask for the format part of the NovbLongHeader.message_type field +}; // clang-format on + +/** + * @brief Message type format (bit 7 of NovbLongHeader.message_type) + */ +enum class NovbMsgTypeResp : uint8_t +{ // clang-format off + ORIGINAL = 0b00000000, //!< Primary GNSS receiver + RESPONSE = 0b10000000, //!< Secondary GNSS receiver + _MASK = 0b10000000, //!< Mask for the response part of the NovbLongHeader.message_type field +}; // clang-format on + +/** + * @brief Message time status (NovbLongHeader.time_status) + * + * See https://docs.novatel.com/OEM7/Content/Messages/GPS_Reference_Time_Statu.htm#Table_GPSReferenceTimeStatus + */ +enum class NovbTimeStatus : uint8_t +{ // clang-format off + UNKNOWN = 20, //!< Time validity is unknown + APPROXIMATE = 60, //!< Time is set approximately + COARSEADJUSTING = 80, //!< Time is approaching coarse precision + COARSE = 100, //!< This time is valid to coarse precision + COARSESTEERING = 120, //!< Time is coarse set and is being steered + FREEWHEELING = 130, //!< Position is lost and the range bias cannot be calculated + FINEADJUSTING = 140, //!< Time is adjusting to fine precision + FINE = 160, //!< Time has fine precision + FINEBACKUPSTEERING = 170, //!< Time is fine set and is being steered by the backup system + FINESTEERING = 180, //!< Time is fine set and is being steered + SATTIME = 200, //!< Time from satellite. Only used in logs containing satellite data, such as eph or alm +}; // clang-format on + +/** + * @brief Stringify time status + * + * @param[in] time_status The time status + * + * @returns a unique string for the time status + */ +const char* NovbTimeStatusStr(const NovbTimeStatus time_status); + +/** + * @brief Message port address (NovbLongHeader.port_address) + * + * See https://docs.novatel.com/OEM7/Content/Messages/Binary.htm#Table_DetailedPortIdentifier + */ +enum class NovbPortAddr : uint8_t +{ // clang-format off + NO_PORTS = 0x00, //!< No ports specified + ALL_PORTS = 0x80, //!< All virtual ports for all ports + THISPORT = 0xc0, //!< Current COM port + // There are many more... +}; // clang-format on + +// --------------------------------------------------------------------------------------------------------------------- + +/** + * @brief Solution status + * + * See https://docs.novatel.com/OEM7/Content/Logs/BESTPOS.htm#SolutionStatus + */ +enum class NovbGnssSolStat : uint32_t +{ // clang-format off + SOL_COMPUTED = 0, //!< Solution computed + INSUFFICIENT_OBS = 1, //!< Insufficient observations + NO_CONVERGENCE = 2, //!< No convergence + SINGULARITY = 3, //!< Singularity at parameters matrix + COV_TRACE = 4, //!< Covariance trace exceeds maximum (trace > 1000 m) + TEST_DIST = 5, //!< Test distance exceeded (maximum of 3 rejections if distance >10 km) + COLD_START = 6, //!< Not yet converged from cold start + V_H_LIMIT = 7, //!< Height or velocity limits exceeded (in accordance with export licensing restrictions) + VARIANCE = 8, //!< Variance exceeds limits + RESIDUALS = 9, //!< Residuals are too large + // There are some more... +}; // clang-format on + +/** + * @brief Extended solution status (bits) + * + * See https://docs.novatel.com/OEM7/Content/Logs/BESTPOS.htm#ExtendedSolutionStatus + */ +enum class NovbGnssSolExtStat : uint8_t +{ // clang-format off + SOL_VERIFIED = 0b00000001, //!< Solution verified + // There are more... +}; // clang-format on + +/** + * @brief Solution source (bits) + * + * See https://docs.novatel.com/OEM7/Content/Logs/HEADING2.htm#SolutionSource + */ +enum class NovbSolSource : uint8_t +{ // clang-format off + PRIMARY = 0b00000100, //!< Primary antenna + SECONDARY = 0b00001000, //!< Secondary antenna + _MASK = 0b00001100, //!< Mask +}; // clang-format on + +/** + * @brief Datum ID + */ +enum class NovbDatumId : uint32_t +{ // clang-format off + WGS84 = 61, //!< WGS-84 datum + USER = 63, //!< User-defined datum +}; // clang-format on + +/** + * @brief Position or velocity type + * + * See https://docs.novatel.com/OEM7/Content/Logs/BESTPOS.htm#Position_VelocityType + */ +enum class NovbPosOrVelType : uint32_t +{ // clang-format off + NONE = 0, //!< No solution + FIXEDPOS = 1, //!< Position has been fixed by the FIX position command or by position averaging. + FIXEDHEIGHT = 2, //!< Position has been fixed by the FIX height or FIX auto command or by position averaging + DOPPLER_VELOCITY = 8, //!< Velocity computed using instantaneous Doppler + SINGLE = 16, //!< Solution calculated using only data supplied by the GNSS satellites + PSRDIFF = 17, //!< Solution calculated using pseudorange differential (DGPS, DGNSS) corrections + WAAS = 18, //!< Solution calculated using corrections from an SBAS satellite + PROPAGATED = 19, //!< Propagated by a Kalman filter without new observations + L1_FLOAT = 32, //!< Single-frequency RTK solution with unresolved, float carrier phase ambiguities + NARROW_FLOAT = 34, //!< Multi-frequency RTK solution with unresolved, float carrier phase ambiguities + L1_INT = 48, //!< Single-frequency RTK solution with carrier phase ambiguities resolved to integers + WIDE_INT = 49, //!< Multi-frequency RTK solution with carrier phase ambiguities resolved to wide-lane integers + NARROW_INT = 50, //!< Multi-frequency RTK solution with carrier phase ambiguities resolved to narrow-lane integers + RTK_DIRECT_INS = 51, //!< RTK status where the RTK filter is directly initialized from the INS filter + INS_SBAS = 52, //!< INS position, where the last applied position update used a GNSS solution computed using corrections from an SBAS (WAAS) solution + INS_PSRSP = 53, //!< INS position, where the last applied position update used a single point GNSS (SINGLE) solution + INS_PSRDIFF = 54, //!< INS position, where the last applied position update used a pseudorange differential GNSS (PSRDIFF) solution + INS_RTKFLOAT = 55, //!< INS position, where the last applied position update used a floating ambiguity RTK (L1_FLOAT or NARROW_FLOAT) solution + INS_RTKFIXED = 56, //!< INS position, where the last applied position update used a fixed integer ambiguity RTK (L1_INT, WIDE_INT or NARROW_INT) solution + PPP_CONVERGING = 68, //!< Converging TerraStar-C, TerraStar-C PRO or TerraStar-X solution + PPP = 69, //!< Converged TerraStar-C, TerraStar-C PRO or TerraStar-X solution + OPERATIONAL = 70, //!< Solution accuracy is within UAL operational limit + WARNING = 71, //!< Solution accuracy is outside UAL operational limit but within warning limit + OUT_OF_BOUNDS = 72, //!< Solution accuracy is outside UAL limits + INS_PPP_CONVERGING = 73, //!< INS position, where the last applied position update used a converging TerraStar-C, TerraStar-C PRO or TerraStar-X PPP (PPP_CONVERGING) solution + INS_PPP = 74, //!< INS position, where the last applied position update used a converged TerraStar-C, TerraStar-C PRO or TerraStar-X PPP (PPP) solution + PPP_BASIC_CONVERGING = 77, //!< Converging TerraStar-L solution + PPP_BASIC = 78, //!< Converged TerraStar-L solution + INS_PPP_BASIC_CONVERGING = 79, //!< INS position, where the last applied position update used a converging TerraStar-L PPP (PPP_BASIC) solution + INS_PPP_BASIC = 80, //!< INS position, where the last applied position update used a converged TerraStar-L PPP (PPP_BASIC) solution +}; // clang-format on + +/** + * @brief GPS and GLONASS signals used (bits) + * + * See https://docs.novatel.com/OEM7/Content/Logs/BESTPOS.htm#GPS_GLONASSSignalUsedMask + */ +enum class NovbSigUsedGpsGlo : uint8_t +{ // clang-format off + GPS_L1 = 0x01, //!< GPS L1 used in solution + GPS_L2 = 0x02, //!< GPS L2 used in solution + GPS_L5 = 0x04, //!< GPS L5 used in solution + GLONASS_L1 = 0x10, //!< GLONASS L1 used in solution + GLONASS_L2 = 0x20, //!< GLONASS L2 used in solution + GLONASS_L5 = 0x40, //!< GLONASS L3 used in solution +}; // clang-format on + +/** + * @brief Gelileo and BeiDou signals used (bits) + * + * See https://docs.novatel.com/OEM7/Content/Logs/BESTPOS.htm#Galileo_BeiDouSignalUsedMask + */ +enum class NovbSigUsedGalBds : uint8_t +{ // clang-format off + GALILEO_L1 = 0x01, //!< Galileo E1 used in Solution + GALILEO_L2 = 0x02, //!< Galileo E5a used in Solution + GALILEO_L5 = 0x04, //!< Galileo E5b used in Solution + GALILEO_ALTBOC = 0x08, //!< Galileo ALTBOC used in Solution + BEIDOU_L1 = 0x10, //!< BeiDou B1 used in Solution (B1I and B1C) + BEIDOU_L2 = 0x20, //!< BeiDou B2 used in Solution (B2I, B2a and B2b) + BEIDOU_L5 = 0x40, //!< BeiDou B3 used in Solution (B3I) + GALILEO_E6 = 0x80, //!< Galileo E6 used in Solution (E6B and E6C) +}; // clang-format on + +/** + * @brief Intertial solution status + * + * See https://docs.novatel.com/OEM7/Content/SPAN_Logs/INSATT.htm#InertialSolutionStatus + */ +enum class NovbInsSolStatus : uint32_t +{ // clang-format off + INS_INACTIVE = 0, //!< IMU logs are present, but the alignment routine has not started; INS is inactive + INS_ALIGNING = 1, //!< INS is in alignment mode + INS_HIGH_VARIANCE = 2, //!< The INS solution uncertainty contains outliers and the solution may be outside specifications + INS_SOLUTION_GOOD = 3, //!< The INS filter is in navigation mode and the INS solution is good + INS_SOLUTION_FREE = 6, //!< The INS Filter is in navigation mode and the GNSS solution is suspected to be in error + INS_ALIGNMENT_COMPLETE = 7, //!< The INS filter is in navigation mode, but not enough vehicle dynamics have been experienced for the system to be within specifications + DETERMINING_ORIENTATION = 8, //!< INS is determining the IMU axis aligned with gravity + WAITING_INITIAL_POS = 9, //!< The INS filter has determined the IMU orientation and is awaiting an initial position estimate to begin the alignment process + WAITING_AZIMUTH = 10, //!< The INS filer has orientation, initial biases, initial position and valid roll/pitch estimated + INITIALIZING_BIASES = 11, //!< The INS filter is estimating initial biases during the first 10 seconds of stationary data + MOTION_DETECT = 12, //!< The INS filter has not completely aligned, but has detected motion + WAITING_ALIGNMENTORIENTATION = 14, //!< The INS filter is waiting to start alignment +}; // clang-format on + +/** + * @brief Extended intertial solution status (bits) + * + * See https://docs.novatel.com/OEM7/Content/SPAN_Logs/INSATTX.htm#ExtendedSolutionStatus + */ +enum class NovbInsSolExtStatus : uint32_t +{ // clang-format off + POSITION_UPDATE = 0x00000001, //!< Position update + PHASE_UPDATE = 0x00000002, //!< Phase update + ZERO_VELOCITY_UPDATE = 0x00000004, //!< Zero velocity update + WHEEL_SENSOR_UPDATE = 0x00000008, //!< Wheel sensor update + HEADING_UPDATE = 0x00000010, //!< ALIGN (heading) update + EXTERNAL_POSITION_UPDATE = 0x00000020, //!< External position update + INS_SOLUTION_CONVERGENCE = 0x00000040, //!< INS solution convergence flag + DOPPLER_UPDATE = 0x00000080, //!< Doppler update + PSEUDORANGE_UPDATE = 0x00000100, //!< Pseudorange update + VELOCITY_UPDATE = 0x00000200, //!< Velocity update + DR_UPDATE = 0x00000800, //!< Dead reckoning update + PHASE_WINDUP_UPDATE = 0x00001000, //!< Phase wind up update + COURSE_OVER_GROUND_UPDATE = 0x00002000, //!< Course over ground update + EXTERNAL_VELOCITY_UPDATE = 0x00004000, //!< External velocity update + EXTERNAL_ATTITUDE_UPDATE = 0x00008000, //!< External attitude update + EXTERNAL_HEADING_UPDATE = 0x00010000, //!< External heading update + EXTERNAL_HEIGHT_UPDATE = 0x00020000, //!< External height update + SECONDARY_INS_USED = 0x00400000, //!< Secondary INS solution + TURN_ON_BIAS_ESTIMATED = 0x01000000, //!< Turn on biases estimated + ALIGNMENT_DIRECTION_VERIFIED = 0x02000000, //!< Alignment direction verified + ALIGNMENT_INDICATION_1 = 0x04000000, //!< Alignment indication 1 + ALIGNMENT_INDICATION_2 = 0x08000000, //!< Alignment indication 2 + ALIGNMENT_INDICATION_3 = 0x10000000, //!< Alignment indication 3 + NVM_SEED_INDICATION_1 = 0x20000000, //!< NVM seed indication 1 + NVM_SEED_INDICATION_2 = 0x40000000, //!< NVM seed indication 2 + NVM_SEED_INDICATION_3 = 0x80000000, //!< NVM seed indication 3 +}; // clang-format on + +// --------------------------------------------------------------------------------------------------------------------- + +/** + * @brief NOV_B-RAWDMI payload + * + * See https://docs.novatel.com/OEM7/Content/SPAN_Logs/RAWDMI.htm + */ +struct NovbRawdmi +{ // clang-format off + int32_t dmi1; //!< DMI1 value (RC wheel or FR wheel) + int32_t dmi2; //!< DMI2 value (FL wheel or YW sensor) + int32_t dmi3; //!< DMI3 value (RR wheel) + int32_t dmi4; //!< DMI4 value (RL wheel) + uint32_t dmi1_valid : 1; //!< DMI1 value valid flag (1 = dmi1 value is valid) + uint32_t dmi2_valid : 1; //!< DMI2 value valid flag (1 = dmi2 value is valid) + uint32_t dmi3_valid : 1; //!< DMI3 value valid flag (1 = dmi3 value is valid) + uint32_t dmi4_valid : 1; //!< DMI4 value valid flag (1 = dmi4 value is valid) + uint32_t dmi1_type : 7; //!< DMI1 value type (0 = linear speed, 1 = angular velocity) + uint32_t dmi2_type : 7; //!< DMI2 value type (0 = linear speed, 1 = angular velocity) + uint32_t dmi3_type : 7; //!< DMI3 value type (0 = linear speed, 1 = angular velocity) + uint32_t dmi4_type : 7; //!< DMI4 value type (0 = linear speed, 1 = angular velocity) +}; // clang-format on + +static_assert(sizeof(NovbRawdmi) == 20, ""); + +/** + * @brief NOV_B-RAWIMU payload + * + * See https://docs.novatel.com/OEM7/Content/SPAN_Logs/RAWIMU.htm + */ +struct NOV_B_PACKED NovbRawimu +{ // clang-format off + uint32_t week; //!< GNSS week number + double seconds; //!< GNSS time of week [s] + uint32_t imu_stat; //!< The status of the IMU + int32_t z_accel; //!< Change in velocity count along z axis + int32_t y_accel; //!< -change in velocity count along y axis + int32_t x_accel; //!< Change in velocity count along x axis + int32_t z_gyro; //!< Change in angle count around z axis + int32_t y_gyro; //!< -change in angle count around y axis + int32_t x_gyro; //!< Change in angle count around x axis +}; // clang-format on + +static_assert(sizeof(NovbRawimu) == 40, ""); + +/** + * @brief NOV_B-BESTGNSSPOS payload + * + * See https://docs.novatel.com/OEM7/Content/SPAN_Logs/BESTGNSSPOS.htm + */ +struct NovbBestgnsspos +{ // clang-format off + uint32_t sol_stat; //!< See NovbGnssSolStat + uint32_t pos_type; //!< See NovbPosOrVelType + double lat; //!< @todo document + double lon; //!< @todo document + double hgt; //!< @todo document + float undulation; //!< @todo document + uint32_t datum_id; //!< See NovbDatumId + float lat_stdev; //!< @todo document + float lon_stdev; //!< @todo document + float hgt_stdev; //!< @todo document + uint8_t stn_id[4]; //!< @todo document + float diff_age; //!< @todo document + float sol_age; //!< @todo document + uint8_t num_svs; //!< @todo document + uint8_t num_sol_svs; //!< @todo document + uint8_t num_sol_l1_svs; //!< @todo document + uint8_t num_sol_multi_svs; //!< @todo document + uint8_t reserved; //!< @todo document + uint8_t ext_sol_stat; //!< See NovbGnssSolExtStat + uint8_t galileo_beidou_sig_mask; //!< See NovbSigUsedGalBds + uint8_t gps_glonass_sig_mask; //!< See NovbSigUsedGpsGlo +}; // clang-format on + +static_assert(sizeof(NovbBestgnsspos) == 72, ""); + +/** + * @brief NOV_B-BESTVEL payload + * + * See https://docs.novatel.com/OEM7/Content/Logs/BESTVEL.htm + */ +struct NOV_B_PACKED NovbBestvel +{ // clang-format off + uint32_t sol_stat; //!< See NovbGnssSolStat + uint32_t vel_type; //!< See NovbPosOrVelType + float latency; //!< @todo document + float age; //!< @todo document + double hor_spd; //!< @todo document + double trk_gnd; //!< @todo document + double vert_spd; //!< @todo document + uint32_t reserved; //!< @todo document +}; // clang-format on + +static_assert(sizeof(NovbBestvel) == 44, ""); + +/** + * @brief NOV_B-HEADING2 payload + * + * See https://docs.novatel.com/OEM7/Content/Logs/HEADING2.htm + */ +struct NovbHeading2 +{ // clang-format off + uint32_t sol_status; //!< See NovbGnssSolStat + uint32_t pos_type; //!< See NovbPosOrVelType + float length; //!< @todo document + float heading; //!< @todo document + float pitch; //!< @todo document + float reserved; //!< @todo document + float heading_stdev; //!< @todo document + float pitch_stdev; //!< @todo document + uint8_t rover_stn_id[4]; //!< @todo document + uint8_t master_stn_id[4]; //!< @todo document + uint8_t num_sv_tracked; //!< @todo document + uint8_t num_sv_in_sol; //!< @todo document + uint8_t num_sv_obs; //!< @todo document + uint8_t num_sv_multi; //!< @todo document + uint8_t sol_source; //!< See NovbSolSource + uint8_t ext_sol_status; //!< See NovbGnssSolExtStat + uint8_t galileo_beidou_sig_mask; //!< See NovbSigUsedGalBds + uint8_t gps_glonass_sig_mask; //!< See NovbSigUsedGpsGlo +}; // clang-format on + +static_assert(sizeof(NovbHeading2) == 48, ""); + +/** + * @brief NOV_B-INSPVAX payload + * + * See https://docs.novatel.com/OEM7/Content/SPAN_Logs/INSPVAX.htm + */ +struct NOV_B_PACKED NovbInspvax +{ // clang-format off + uint32_t ins_status; //!< See NovbInsSolStatus + uint32_t pos_type; //!< See NovbPosOrVelType + double latitude; //!< @todo document + double longitude; //!< @todo document + double height; //!< @todo document + float undulation; //!< @todo document + double north_velocity; //!< @todo document + double east_velocity; //!< @todo document + double up_velocity; //!< @todo document + double roll; //!< @todo document + double pitch; //!< @todo document + double azimuth; //!< @todo document + float latitude_stdev; //!< @todo document + float longitude_stdev; //!< @todo document + float height_stdev; //!< @todo document + float north_velocity_stdev; //!< @todo document + float east_velocity_stdev; //!< @todo document + float up_velocity_stdev; //!< @todo document + float roll_stdev; //!< @todo document + float pitch_stdev; //!< @todo document + float azimuth_stdev; //!< @todo document + uint32_t extended_status; //!< See NovbInsSolExtStatus + uint16_t time_since_update; //!< @todo document +}; // clang-format on + +static_assert(sizeof(NovbInspvax) == 126, ""); + +#undef NOV_B_PACKED + +/* ****************************************************************************************************************** */ +} // namespace novb +} // namespace parser +} // namespace common +} // namespace fpsdk +#endif // __FPSDK_COMMON_PARSER_NOVB_HPP__ diff --git a/fpsdk_common/include/fpsdk_common/parser/rtcm3.hpp b/fpsdk_common/include/fpsdk_common/parser/rtcm3.hpp new file mode 100644 index 0000000..102d8fc --- /dev/null +++ b/fpsdk_common/include/fpsdk_common/parser/rtcm3.hpp @@ -0,0 +1,538 @@ +/** + * \verbatim + * ___ ___ + * \ \ / / + * \ \/ / Copyright (c) Fixposition AG (www.fixposition.com) and contributors + * / /\ \ License: see the LICENSE file + * /__/ \__\ + * + * Based on work by flipflip (https://github.com/phkehl) + * The information on message structures, IDs, descriptions etc. in this file are from publicly available data, such as: + * - RTCM (https://www.rtcm.org/publications) + * - https://www.use-snip.com/kb/knowledge-base/rtcm-3-message-list/ + * - Forums, stackoverflow, et al. + * \endverbatim + * + * @file + * @brief Fixposition SDK: Parser RTCM3 routines and types + * + * @page FPSDK_COMMON_PARSER_RTCM3 Parser RTCM3 routines and types + * + * **API**: fpsdk_common/parser/rtcm3.hpp and fpsdk::common::parser::rtcm3 + * + */ +#ifndef __FPSDK_COMMON_PARSER_RTCM3_HPP__ +#define __FPSDK_COMMON_PARSER_RTCM3_HPP__ + +/* LIBC/STL */ +#include + +/* EXTERNAL */ + +/* PACKAGE */ + +namespace fpsdk { +namespace common { +namespace parser { +/** + * @brief Parser RTCM3 routines and types + */ +namespace rtcm3 { +/* ****************************************************************************************************************** */ + +static constexpr uint8_t RTCM3_PREAMBLE = 0xd3; //!< RTCM3 frame preamble +static constexpr std::size_t RTCM3_HEAD_SIZE = 3; //!< Size of RTCM3 header (in bytes) +static constexpr std::size_t RTCM3_FRAME_SIZE = (RTCM3_HEAD_SIZE + 3); //!< Size of RTCM3 frame + +/** + * @brief Get RTCM3 message type (DF002, 12 bits, unsigned) + * + * @param[in] msg Pointer to the start of the message + * + * @note No check on the data provided is done. The caller must ensure that the data is a valid RTCM3 message. + * + * @returns the RTCM3 message type + */ +constexpr uint16_t Rtcm3Type(const uint8_t* msg) +{ + return (((uint16_t)(((uint8_t*)(msg))[RTCM3_HEAD_SIZE + 0]) << 4) | + (uint16_t)((((uint8_t*)(msg))[RTCM3_HEAD_SIZE + 1] >> 4) & 0x0f)); +} + +/** + * @brief Get sub-type for a RTCM3 message (like the type 4072) + * + * @param[in] msg Pointer to the start of the message + * + * @note No check on the data provided is done. The caller must ensure that the data is a valid RTCM3 message with a + * sub-type DF002 as the first field. + * + * @returns the sub-type of a RTCM3 message + */ +constexpr uint16_t Rtcm3SubType(const uint8_t* msg) +{ + return ( + ((uint16_t)(((uint8_t*)(msg))[RTCM3_HEAD_SIZE + 1] & 0x0f) << 8) | (((uint8_t*)(msg))[RTCM3_HEAD_SIZE + 2])); +} + +/** + * @brief Get RTCM3 message name + * + * Generates a name (string) in the form "RTCM-TYPENNNN_P", where NNNN is the message type and _P a suffix for some + * proprietary messages (for example, RTCM3-TYPE4072_0 for sub-type 0 of that message). + * + * @param[out] name String to write the name to + * @param[in] size Size of \c name (incl. nul termination) + * @param[in] msg Pointer to the RTCM3 message + * @param[in] msg_size Size of the \c msg + * + * @note No check on the data provided is done. The caller must ensure that the data is a valid RTCM3 message. + * + * @returns true if message name was generated, false if \c name buffer was too small + */ +bool Rtcm3GetMessageName(char* name, const std::size_t size, const uint8_t* msg, const std::size_t msg_size); + +/** + * @brief Get RTCM3 message info + * + * This stringifies the content of some RTCM3 messages, for debugging. + * + * @param[out] info String to write the info to + * @param[in] size Size of \c name (incl. nul termination) + * @param[in] msg Pointer to the RTCM3 message + * @param[in] msg_size Size of the \c msg + * + * @note No check on the data provided is done. The caller must ensure that the data is a valid RTCM3 message. + * + * @returns true if message info was generated (even if info is empty), false if \c name buffer was too small + */ +bool Rtcm3GetMessageInfo(char* info, const std::size_t size, const uint8_t* msg, const std::size_t msg_size); + +/** + * @brief Get description for a RTCM3 message type + * + * @param[in] type Message type + * @param[in] subtype Message sub-type (if appropriate) + * + * @return the description of the message type, if available, NULL otherwise + */ +const char* Rtcm3GetTypeDesc(const uint16_t type, const uint16_t subtype = 0xffff); + +/** + * @brief Get RTCM3 unsigned integer + * + * @param[in] data Pointer to the start of the RTCM3 data (at offset RTCM3_HEAD_SIZE into the message) + * @param[in] offs Offset in [bits] to the start of the value + * @param[in] size Size in [bits] of the value + * + * @returns the unsigned integer value (zero padded 64-bit value) + */ +uint64_t Rtcm3GetUnsigned(const uint8_t* data, const std::size_t offs, const std::size_t size); + +/** + * @brief Get RTCM3 signed integer + * + * @param[in] data Pointer to the start of the RTCM3 data (at offset RTCM3_HEAD_SIZE into the message) + * @param[in] offs Offset in [bits] to the start of the value + * @param[in] size Size in [bits] of the value + * + * @returns the signed integer value (sign-extended 64-bit value) + */ +int64_t Rtcm3GetSigned(const uint8_t* data, const std::size_t offs, const std::size_t size); + +/** + * @brief Count number of set bits + * + * @param[in] mask The value to count the number of set bits in + * + * @returns the number of set (non-zero) bits in the value + */ +std::size_t Rtcm3CountBits(const uint64_t mask); + +/** + * @brief Antenna reference point + */ +struct Rtcm3Arp +{ + int ref_sta_id_; //!< Reference station ID + double ecef_x_; //!< ECEF X [m] + double ecef_y_; //!< ECEF Y [m] + double ecef_z_; //!< ECEF Z [m] +}; + +/** + * @brief Get ARP from message types 1005, 1006 or 1032 + * + * @param[in] msg The raw RTCM3 message + * @param[out] arp The header information + * + * @returns true if the ARP was successfully extracted, false otherwise + */ +bool Rtcm3GetArp(const uint8_t* msg, Rtcm3Arp& arp); + +/** + * @brief Antenna info + */ +struct Rtcm3Ant // clang-format off +{ + int ref_sta_id_; //!< @todo documentation + char ant_desc_[32]; //!< @todo documentation + char ant_serial_[32]; //!< @todo documentation + uint8_t ant_setup_id_; //!< @todo documentation + char rx_type_[32]; //!< @todo documentation + char rx_fw_[32]; //!< @todo documentation + char rx_serial_[32]; //!< @todo documentation +}; // clang-format on + +/** + * @brief Get (some) antenna info from message type 1007, 1008 or 1033 + * + * @param[in] msg The raw RTCM3 message + * @param[out] ant The antenna information + * + * @returns true if the antenna info was successfully extracted, false otherwise + */ +bool Rtcm3GetAnt(const uint8_t* msg, Rtcm3Ant& ant); + +/** + * @brief RTCM3 MSM messages GNSS + */ +enum class Rtcm3MsmGnss : uint16_t +{ // clang-format off + GPS = 70, //!< GPS + GLO = 80, //!< GLONASS + GAL = 90, //!< Galileo + SBAS = 100, //!< SBAS + QZSS = 110, //!< QZSS + BDS = 120, //!< BeiDou + NAVIC = 130, //!< NavIC +}; // clang-format on + +/** + * @brief RTCM3 MSM messages type + */ +enum class Rtcm3MsmType : uint16_t +{ + MSM1 = 1, //!< Type 1 (C) + MSM2 = 2, //!< Type 2 (L) + MSM3 = 3, //!< Type 3 (C, L) + MSM4 = 4, //!< Type 4 (full C, full L, S) + MSM5 = 5, //!< Type 5 (full C, full L, S, D) + MSM6 = 6, //!< Type 6 (ext full C, ext full L, S) + MSM7 = 7, //!< Type 7 (ext full C, ext full L, S, D) +}; + +/** + * @brief RTMC3 message type to MSM GNSS and type + * + * @param[in] msg_type The RTMC3 message type + * @param[out] gnss The GNSS (or NULL) + * @param[out] msm The MSM type (number) (or NULL) + * + * @returns true if msgType was a valid and known RTCM3 MSM message + */ +bool Rtcm3TypeToMsm(uint16_t msg_type, Rtcm3MsmGnss& gnss, Rtcm3MsmType& msm); + +/** + * @brief RTCM3 MSM messages common header + */ +struct Rtcm3MsmHeader +{ + Rtcm3MsmGnss gnss_; //!< GNSS + Rtcm3MsmType msm_; //!< MSM + + uint16_t msg_type_; //!< Message number (DF002, uint12) + uint16_t ref_sta_id_; //!< Reference station ID (DF003, uint12) + union + { + double any_tow_; //!< Any time of week [s] + double gps_tow_; //!< GPS time of week [s] (DF004 uint30 [ms]) + double sbas_tow_; //!< SBAS time of week [s] (DF004 uint30 [ms]) + double glo_tow_; //!< GLONASS time of week [s] (DF416 uint3 [d], DF034 uint27 [ms]) + double gal_tow_; //!< Galileo time of week [s] (DF248 uint30 [ms]) + double qzss_tow_; //!< QZSS time of week [s] (DF428 uint30 [ms]) + double bds_tow_; //!< BeiDou time of week [s] (DF427 uint30 [ms]) + }; + bool multi_msg_bit_; //!< Multiple message bit (DF393, bit(1)) + uint8_t iods_; //!< IODS, issue of data station (DF409, uint3) + uint8_t clk_steering_; //!< Clock steering indicator (DF411, uint2) + uint8_t ext_clock_; //!< External clock indicator (DF412, uint2) + bool smooth_; //!< GNSS divergence-free smoothing indicator (DF417, bit(1)) + uint8_t smooth_int_; //!< GNSS smoothing interval (DF418, bit(3)) + uint64_t sat_mask_; //!< GNSS satellite mask (DF394, bit(64)) + uint64_t sig_mask_; //!< GNSS signal mask (DF395, bit(64)) + uint64_t cell_mask_; //!< GNSS cell mask (DF396, bit(64)) + + int num_sat_; //!< Number of satellites (in satMask) + int num_sig_; //!< Number of signals (in sigMask) + int num_cell_; //!< Number of cells (in cellMask) +}; + +/** + * @brief Extract RTCM3 MSM message common header + * + * @param[in] msg The raw RTCM3 message + * @param[out] header The header information + * + * @returns true if the header was successfully extracted, false otherwise + */ +bool Rtcm3GetMsmHeader(const uint8_t* msg, Rtcm3MsmHeader& header); + +/** + * @name RTCM3 messages (names and IDs) + * + * @{ + */ +// clang-format off +// @fp_codegen_begin{FPSDK_COMMON_PARSER_RTCM3_MESSAGES} +static constexpr uint16_t RTCM3_TYPE1001_MSGID = 1001; //!< RTCM3-TYPE1001 message ID +static constexpr const char* RTCM3_TYPE1001_STRID = "RTCM3-TYPE1001"; //!< RTCM3-TYPE1001 message name +static constexpr uint16_t RTCM3_TYPE1002_MSGID = 1002; //!< RTCM3-TYPE1002 message ID +static constexpr const char* RTCM3_TYPE1002_STRID = "RTCM3-TYPE1002"; //!< RTCM3-TYPE1002 message name +static constexpr uint16_t RTCM3_TYPE1003_MSGID = 1003; //!< RTCM3-TYPE1003 message ID +static constexpr const char* RTCM3_TYPE1003_STRID = "RTCM3-TYPE1003"; //!< RTCM3-TYPE1003 message name +static constexpr uint16_t RTCM3_TYPE1004_MSGID = 1004; //!< RTCM3-TYPE1004 message ID +static constexpr const char* RTCM3_TYPE1004_STRID = "RTCM3-TYPE1004"; //!< RTCM3-TYPE1004 message name +static constexpr uint16_t RTCM3_TYPE1005_MSGID = 1005; //!< RTCM3-TYPE1005 message ID +static constexpr const char* RTCM3_TYPE1005_STRID = "RTCM3-TYPE1005"; //!< RTCM3-TYPE1005 message name +static constexpr uint16_t RTCM3_TYPE1006_MSGID = 1006; //!< RTCM3-TYPE1006 message ID +static constexpr const char* RTCM3_TYPE1006_STRID = "RTCM3-TYPE1006"; //!< RTCM3-TYPE1006 message name +static constexpr uint16_t RTCM3_TYPE1007_MSGID = 1007; //!< RTCM3-TYPE1007 message ID +static constexpr const char* RTCM3_TYPE1007_STRID = "RTCM3-TYPE1007"; //!< RTCM3-TYPE1007 message name +static constexpr uint16_t RTCM3_TYPE1008_MSGID = 1008; //!< RTCM3-TYPE1008 message ID +static constexpr const char* RTCM3_TYPE1008_STRID = "RTCM3-TYPE1008"; //!< RTCM3-TYPE1008 message name +static constexpr uint16_t RTCM3_TYPE1009_MSGID = 1009; //!< RTCM3-TYPE1009 message ID +static constexpr const char* RTCM3_TYPE1009_STRID = "RTCM3-TYPE1009"; //!< RTCM3-TYPE1009 message name +static constexpr uint16_t RTCM3_TYPE1010_MSGID = 1010; //!< RTCM3-TYPE1010 message ID +static constexpr const char* RTCM3_TYPE1010_STRID = "RTCM3-TYPE1010"; //!< RTCM3-TYPE1010 message name +static constexpr uint16_t RTCM3_TYPE1011_MSGID = 1011; //!< RTCM3-TYPE1011 message ID +static constexpr const char* RTCM3_TYPE1011_STRID = "RTCM3-TYPE1011"; //!< RTCM3-TYPE1011 message name +static constexpr uint16_t RTCM3_TYPE1012_MSGID = 1012; //!< RTCM3-TYPE1012 message ID +static constexpr const char* RTCM3_TYPE1012_STRID = "RTCM3-TYPE1012"; //!< RTCM3-TYPE1012 message name +static constexpr uint16_t RTCM3_TYPE1030_MSGID = 1030; //!< RTCM3-TYPE1030 message ID +static constexpr const char* RTCM3_TYPE1030_STRID = "RTCM3-TYPE1030"; //!< RTCM3-TYPE1030 message name +static constexpr uint16_t RTCM3_TYPE1031_MSGID = 1031; //!< RTCM3-TYPE1031 message ID +static constexpr const char* RTCM3_TYPE1031_STRID = "RTCM3-TYPE1031"; //!< RTCM3-TYPE1031 message name +static constexpr uint16_t RTCM3_TYPE1032_MSGID = 1032; //!< RTCM3-TYPE1032 message ID +static constexpr const char* RTCM3_TYPE1032_STRID = "RTCM3-TYPE1032"; //!< RTCM3-TYPE1032 message name +static constexpr uint16_t RTCM3_TYPE1033_MSGID = 1033; //!< RTCM3-TYPE1033 message ID +static constexpr const char* RTCM3_TYPE1033_STRID = "RTCM3-TYPE1033"; //!< RTCM3-TYPE1033 message name +static constexpr uint16_t RTCM3_TYPE1230_MSGID = 1230; //!< RTCM3-TYPE1230 message ID +static constexpr const char* RTCM3_TYPE1230_STRID = "RTCM3-TYPE1230"; //!< RTCM3-TYPE1230 message name +static constexpr uint16_t RTCM3_TYPE1071_MSGID = 1071; //!< RTCM3-TYPE1071 message ID +static constexpr const char* RTCM3_TYPE1071_STRID = "RTCM3-TYPE1071"; //!< RTCM3-TYPE1071 message name +static constexpr uint16_t RTCM3_TYPE1072_MSGID = 1072; //!< RTCM3-TYPE1072 message ID +static constexpr const char* RTCM3_TYPE1072_STRID = "RTCM3-TYPE1072"; //!< RTCM3-TYPE1072 message name +static constexpr uint16_t RTCM3_TYPE1073_MSGID = 1073; //!< RTCM3-TYPE1073 message ID +static constexpr const char* RTCM3_TYPE1073_STRID = "RTCM3-TYPE1073"; //!< RTCM3-TYPE1073 message name +static constexpr uint16_t RTCM3_TYPE1074_MSGID = 1074; //!< RTCM3-TYPE1074 message ID +static constexpr const char* RTCM3_TYPE1074_STRID = "RTCM3-TYPE1074"; //!< RTCM3-TYPE1074 message name +static constexpr uint16_t RTCM3_TYPE1075_MSGID = 1075; //!< RTCM3-TYPE1075 message ID +static constexpr const char* RTCM3_TYPE1075_STRID = "RTCM3-TYPE1075"; //!< RTCM3-TYPE1075 message name +static constexpr uint16_t RTCM3_TYPE1076_MSGID = 1076; //!< RTCM3-TYPE1076 message ID +static constexpr const char* RTCM3_TYPE1076_STRID = "RTCM3-TYPE1076"; //!< RTCM3-TYPE1076 message name +static constexpr uint16_t RTCM3_TYPE1077_MSGID = 1077; //!< RTCM3-TYPE1077 message ID +static constexpr const char* RTCM3_TYPE1077_STRID = "RTCM3-TYPE1077"; //!< RTCM3-TYPE1077 message name +static constexpr uint16_t RTCM3_TYPE1081_MSGID = 1081; //!< RTCM3-TYPE1081 message ID +static constexpr const char* RTCM3_TYPE1081_STRID = "RTCM3-TYPE1081"; //!< RTCM3-TYPE1081 message name +static constexpr uint16_t RTCM3_TYPE1082_MSGID = 1082; //!< RTCM3-TYPE1082 message ID +static constexpr const char* RTCM3_TYPE1082_STRID = "RTCM3-TYPE1082"; //!< RTCM3-TYPE1082 message name +static constexpr uint16_t RTCM3_TYPE1083_MSGID = 1083; //!< RTCM3-TYPE1083 message ID +static constexpr const char* RTCM3_TYPE1083_STRID = "RTCM3-TYPE1083"; //!< RTCM3-TYPE1083 message name +static constexpr uint16_t RTCM3_TYPE1084_MSGID = 1084; //!< RTCM3-TYPE1084 message ID +static constexpr const char* RTCM3_TYPE1084_STRID = "RTCM3-TYPE1084"; //!< RTCM3-TYPE1084 message name +static constexpr uint16_t RTCM3_TYPE1085_MSGID = 1085; //!< RTCM3-TYPE1085 message ID +static constexpr const char* RTCM3_TYPE1085_STRID = "RTCM3-TYPE1085"; //!< RTCM3-TYPE1085 message name +static constexpr uint16_t RTCM3_TYPE1086_MSGID = 1086; //!< RTCM3-TYPE1086 message ID +static constexpr const char* RTCM3_TYPE1086_STRID = "RTCM3-TYPE1086"; //!< RTCM3-TYPE1086 message name +static constexpr uint16_t RTCM3_TYPE1087_MSGID = 1087; //!< RTCM3-TYPE1087 message ID +static constexpr const char* RTCM3_TYPE1087_STRID = "RTCM3-TYPE1087"; //!< RTCM3-TYPE1087 message name +static constexpr uint16_t RTCM3_TYPE1091_MSGID = 1091; //!< RTCM3-TYPE1091 message ID +static constexpr const char* RTCM3_TYPE1091_STRID = "RTCM3-TYPE1091"; //!< RTCM3-TYPE1091 message name +static constexpr uint16_t RTCM3_TYPE1092_MSGID = 1092; //!< RTCM3-TYPE1092 message ID +static constexpr const char* RTCM3_TYPE1092_STRID = "RTCM3-TYPE1092"; //!< RTCM3-TYPE1092 message name +static constexpr uint16_t RTCM3_TYPE1093_MSGID = 1093; //!< RTCM3-TYPE1093 message ID +static constexpr const char* RTCM3_TYPE1093_STRID = "RTCM3-TYPE1093"; //!< RTCM3-TYPE1093 message name +static constexpr uint16_t RTCM3_TYPE1094_MSGID = 1094; //!< RTCM3-TYPE1094 message ID +static constexpr const char* RTCM3_TYPE1094_STRID = "RTCM3-TYPE1094"; //!< RTCM3-TYPE1094 message name +static constexpr uint16_t RTCM3_TYPE1095_MSGID = 1095; //!< RTCM3-TYPE1095 message ID +static constexpr const char* RTCM3_TYPE1095_STRID = "RTCM3-TYPE1095"; //!< RTCM3-TYPE1095 message name +static constexpr uint16_t RTCM3_TYPE1096_MSGID = 1096; //!< RTCM3-TYPE1096 message ID +static constexpr const char* RTCM3_TYPE1096_STRID = "RTCM3-TYPE1096"; //!< RTCM3-TYPE1096 message name +static constexpr uint16_t RTCM3_TYPE1097_MSGID = 1097; //!< RTCM3-TYPE1097 message ID +static constexpr const char* RTCM3_TYPE1097_STRID = "RTCM3-TYPE1097"; //!< RTCM3-TYPE1097 message name +static constexpr uint16_t RTCM3_TYPE1101_MSGID = 1101; //!< RTCM3-TYPE1101 message ID +static constexpr const char* RTCM3_TYPE1101_STRID = "RTCM3-TYPE1101"; //!< RTCM3-TYPE1101 message name +static constexpr uint16_t RTCM3_TYPE1102_MSGID = 1102; //!< RTCM3-TYPE1102 message ID +static constexpr const char* RTCM3_TYPE1102_STRID = "RTCM3-TYPE1102"; //!< RTCM3-TYPE1102 message name +static constexpr uint16_t RTCM3_TYPE1103_MSGID = 1103; //!< RTCM3-TYPE1103 message ID +static constexpr const char* RTCM3_TYPE1103_STRID = "RTCM3-TYPE1103"; //!< RTCM3-TYPE1103 message name +static constexpr uint16_t RTCM3_TYPE1104_MSGID = 1104; //!< RTCM3-TYPE1104 message ID +static constexpr const char* RTCM3_TYPE1104_STRID = "RTCM3-TYPE1104"; //!< RTCM3-TYPE1104 message name +static constexpr uint16_t RTCM3_TYPE1105_MSGID = 1105; //!< RTCM3-TYPE1105 message ID +static constexpr const char* RTCM3_TYPE1105_STRID = "RTCM3-TYPE1105"; //!< RTCM3-TYPE1105 message name +static constexpr uint16_t RTCM3_TYPE1106_MSGID = 1106; //!< RTCM3-TYPE1106 message ID +static constexpr const char* RTCM3_TYPE1106_STRID = "RTCM3-TYPE1106"; //!< RTCM3-TYPE1106 message name +static constexpr uint16_t RTCM3_TYPE1107_MSGID = 1107; //!< RTCM3-TYPE1107 message ID +static constexpr const char* RTCM3_TYPE1107_STRID = "RTCM3-TYPE1107"; //!< RTCM3-TYPE1107 message name +static constexpr uint16_t RTCM3_TYPE1111_MSGID = 1111; //!< RTCM3-TYPE1111 message ID +static constexpr const char* RTCM3_TYPE1111_STRID = "RTCM3-TYPE1111"; //!< RTCM3-TYPE1111 message name +static constexpr uint16_t RTCM3_TYPE1112_MSGID = 1112; //!< RTCM3-TYPE1112 message ID +static constexpr const char* RTCM3_TYPE1112_STRID = "RTCM3-TYPE1112"; //!< RTCM3-TYPE1112 message name +static constexpr uint16_t RTCM3_TYPE1113_MSGID = 1113; //!< RTCM3-TYPE1113 message ID +static constexpr const char* RTCM3_TYPE1113_STRID = "RTCM3-TYPE1113"; //!< RTCM3-TYPE1113 message name +static constexpr uint16_t RTCM3_TYPE1114_MSGID = 1114; //!< RTCM3-TYPE1114 message ID +static constexpr const char* RTCM3_TYPE1114_STRID = "RTCM3-TYPE1114"; //!< RTCM3-TYPE1114 message name +static constexpr uint16_t RTCM3_TYPE1115_MSGID = 1115; //!< RTCM3-TYPE1115 message ID +static constexpr const char* RTCM3_TYPE1115_STRID = "RTCM3-TYPE1115"; //!< RTCM3-TYPE1115 message name +static constexpr uint16_t RTCM3_TYPE1116_MSGID = 1116; //!< RTCM3-TYPE1116 message ID +static constexpr const char* RTCM3_TYPE1116_STRID = "RTCM3-TYPE1116"; //!< RTCM3-TYPE1116 message name +static constexpr uint16_t RTCM3_TYPE1117_MSGID = 1117; //!< RTCM3-TYPE1117 message ID +static constexpr const char* RTCM3_TYPE1117_STRID = "RTCM3-TYPE1117"; //!< RTCM3-TYPE1117 message name +static constexpr uint16_t RTCM3_TYPE1121_MSGID = 1121; //!< RTCM3-TYPE1121 message ID +static constexpr const char* RTCM3_TYPE1121_STRID = "RTCM3-TYPE1121"; //!< RTCM3-TYPE1121 message name +static constexpr uint16_t RTCM3_TYPE1122_MSGID = 1122; //!< RTCM3-TYPE1122 message ID +static constexpr const char* RTCM3_TYPE1122_STRID = "RTCM3-TYPE1122"; //!< RTCM3-TYPE1122 message name +static constexpr uint16_t RTCM3_TYPE1123_MSGID = 1123; //!< RTCM3-TYPE1123 message ID +static constexpr const char* RTCM3_TYPE1123_STRID = "RTCM3-TYPE1123"; //!< RTCM3-TYPE1123 message name +static constexpr uint16_t RTCM3_TYPE1124_MSGID = 1124; //!< RTCM3-TYPE1124 message ID +static constexpr const char* RTCM3_TYPE1124_STRID = "RTCM3-TYPE1124"; //!< RTCM3-TYPE1124 message name +static constexpr uint16_t RTCM3_TYPE1125_MSGID = 1125; //!< RTCM3-TYPE1125 message ID +static constexpr const char* RTCM3_TYPE1125_STRID = "RTCM3-TYPE1125"; //!< RTCM3-TYPE1125 message name +static constexpr uint16_t RTCM3_TYPE1126_MSGID = 1126; //!< RTCM3-TYPE1126 message ID +static constexpr const char* RTCM3_TYPE1126_STRID = "RTCM3-TYPE1126"; //!< RTCM3-TYPE1126 message name +static constexpr uint16_t RTCM3_TYPE1127_MSGID = 1127; //!< RTCM3-TYPE1127 message ID +static constexpr const char* RTCM3_TYPE1127_STRID = "RTCM3-TYPE1127"; //!< RTCM3-TYPE1127 message name +static constexpr uint16_t RTCM3_TYPE1131_MSGID = 1131; //!< RTCM3-TYPE1131 message ID +static constexpr const char* RTCM3_TYPE1131_STRID = "RTCM3-TYPE1131"; //!< RTCM3-TYPE1131 message name +static constexpr uint16_t RTCM3_TYPE1132_MSGID = 1132; //!< RTCM3-TYPE1132 message ID +static constexpr const char* RTCM3_TYPE1132_STRID = "RTCM3-TYPE1132"; //!< RTCM3-TYPE1132 message name +static constexpr uint16_t RTCM3_TYPE1133_MSGID = 1133; //!< RTCM3-TYPE1133 message ID +static constexpr const char* RTCM3_TYPE1133_STRID = "RTCM3-TYPE1133"; //!< RTCM3-TYPE1133 message name +static constexpr uint16_t RTCM3_TYPE1134_MSGID = 1134; //!< RTCM3-TYPE1134 message ID +static constexpr const char* RTCM3_TYPE1134_STRID = "RTCM3-TYPE1134"; //!< RTCM3-TYPE1134 message name +static constexpr uint16_t RTCM3_TYPE1135_MSGID = 1135; //!< RTCM3-TYPE1135 message ID +static constexpr const char* RTCM3_TYPE1135_STRID = "RTCM3-TYPE1135"; //!< RTCM3-TYPE1135 message name +static constexpr uint16_t RTCM3_TYPE1136_MSGID = 1136; //!< RTCM3-TYPE1136 message ID +static constexpr const char* RTCM3_TYPE1136_STRID = "RTCM3-TYPE1136"; //!< RTCM3-TYPE1136 message name +static constexpr uint16_t RTCM3_TYPE1137_MSGID = 1137; //!< RTCM3-TYPE1137 message ID +static constexpr const char* RTCM3_TYPE1137_STRID = "RTCM3-TYPE1137"; //!< RTCM3-TYPE1137 message name +static constexpr uint16_t RTCM3_TYPE1019_MSGID = 1019; //!< RTCM3-TYPE1019 message ID +static constexpr const char* RTCM3_TYPE1019_STRID = "RTCM3-TYPE1019"; //!< RTCM3-TYPE1019 message name +static constexpr uint16_t RTCM3_TYPE1020_MSGID = 1020; //!< RTCM3-TYPE1020 message ID +static constexpr const char* RTCM3_TYPE1020_STRID = "RTCM3-TYPE1020"; //!< RTCM3-TYPE1020 message name +static constexpr uint16_t RTCM3_TYPE1042_MSGID = 1042; //!< RTCM3-TYPE1042 message ID +static constexpr const char* RTCM3_TYPE1042_STRID = "RTCM3-TYPE1042"; //!< RTCM3-TYPE1042 message name +static constexpr uint16_t RTCM3_TYPE1044_MSGID = 1044; //!< RTCM3-TYPE1044 message ID +static constexpr const char* RTCM3_TYPE1044_STRID = "RTCM3-TYPE1044"; //!< RTCM3-TYPE1044 message name +static constexpr uint16_t RTCM3_TYPE1045_MSGID = 1045; //!< RTCM3-TYPE1045 message ID +static constexpr const char* RTCM3_TYPE1045_STRID = "RTCM3-TYPE1045"; //!< RTCM3-TYPE1045 message name +static constexpr uint16_t RTCM3_TYPE1046_MSGID = 1046; //!< RTCM3-TYPE1046 message ID +static constexpr const char* RTCM3_TYPE1046_STRID = "RTCM3-TYPE1046"; //!< RTCM3-TYPE1046 message name +static constexpr uint16_t RTCM3_TYPE4050_MSGID = 4050; //!< RTCM3-TYPE4050 message ID +static constexpr const char* RTCM3_TYPE4050_STRID = "RTCM3-TYPE4050"; //!< RTCM3-TYPE4050 message name +static constexpr uint16_t RTCM3_TYPE4051_MSGID = 4051; //!< RTCM3-TYPE4051 message ID +static constexpr const char* RTCM3_TYPE4051_STRID = "RTCM3-TYPE4051"; //!< RTCM3-TYPE4051 message name +static constexpr uint16_t RTCM3_TYPE4052_MSGID = 4052; //!< RTCM3-TYPE4052 message ID +static constexpr const char* RTCM3_TYPE4052_STRID = "RTCM3-TYPE4052"; //!< RTCM3-TYPE4052 message name +static constexpr uint16_t RTCM3_TYPE4053_MSGID = 4053; //!< RTCM3-TYPE4053 message ID +static constexpr const char* RTCM3_TYPE4053_STRID = "RTCM3-TYPE4053"; //!< RTCM3-TYPE4053 message name +static constexpr uint16_t RTCM3_TYPE4054_MSGID = 4054; //!< RTCM3-TYPE4054 message ID +static constexpr const char* RTCM3_TYPE4054_STRID = "RTCM3-TYPE4054"; //!< RTCM3-TYPE4054 message name +static constexpr uint16_t RTCM3_TYPE4055_MSGID = 4055; //!< RTCM3-TYPE4055 message ID +static constexpr const char* RTCM3_TYPE4055_STRID = "RTCM3-TYPE4055"; //!< RTCM3-TYPE4055 message name +static constexpr uint16_t RTCM3_TYPE4056_MSGID = 4056; //!< RTCM3-TYPE4056 message ID +static constexpr const char* RTCM3_TYPE4056_STRID = "RTCM3-TYPE4056"; //!< RTCM3-TYPE4056 message name +static constexpr uint16_t RTCM3_TYPE4057_MSGID = 4057; //!< RTCM3-TYPE4057 message ID +static constexpr const char* RTCM3_TYPE4057_STRID = "RTCM3-TYPE4057"; //!< RTCM3-TYPE4057 message name +static constexpr uint16_t RTCM3_TYPE4058_MSGID = 4058; //!< RTCM3-TYPE4058 message ID +static constexpr const char* RTCM3_TYPE4058_STRID = "RTCM3-TYPE4058"; //!< RTCM3-TYPE4058 message name +static constexpr uint16_t RTCM3_TYPE4059_MSGID = 4059; //!< RTCM3-TYPE4059 message ID +static constexpr const char* RTCM3_TYPE4059_STRID = "RTCM3-TYPE4059"; //!< RTCM3-TYPE4059 message name +static constexpr uint16_t RTCM3_TYPE4060_MSGID = 4060; //!< RTCM3-TYPE4060 message ID +static constexpr const char* RTCM3_TYPE4060_STRID = "RTCM3-TYPE4060"; //!< RTCM3-TYPE4060 message name +static constexpr uint16_t RTCM3_TYPE4061_MSGID = 4061; //!< RTCM3-TYPE4061 message ID +static constexpr const char* RTCM3_TYPE4061_STRID = "RTCM3-TYPE4061"; //!< RTCM3-TYPE4061 message name +static constexpr uint16_t RTCM3_TYPE4062_MSGID = 4062; //!< RTCM3-TYPE4062 message ID +static constexpr const char* RTCM3_TYPE4062_STRID = "RTCM3-TYPE4062"; //!< RTCM3-TYPE4062 message name +static constexpr uint16_t RTCM3_TYPE4063_MSGID = 4063; //!< RTCM3-TYPE4063 message ID +static constexpr const char* RTCM3_TYPE4063_STRID = "RTCM3-TYPE4063"; //!< RTCM3-TYPE4063 message name +static constexpr uint16_t RTCM3_TYPE4064_MSGID = 4064; //!< RTCM3-TYPE4064 message ID +static constexpr const char* RTCM3_TYPE4064_STRID = "RTCM3-TYPE4064"; //!< RTCM3-TYPE4064 message name +static constexpr uint16_t RTCM3_TYPE4065_MSGID = 4065; //!< RTCM3-TYPE4065 message ID +static constexpr const char* RTCM3_TYPE4065_STRID = "RTCM3-TYPE4065"; //!< RTCM3-TYPE4065 message name +static constexpr uint16_t RTCM3_TYPE4066_MSGID = 4066; //!< RTCM3-TYPE4066 message ID +static constexpr const char* RTCM3_TYPE4066_STRID = "RTCM3-TYPE4066"; //!< RTCM3-TYPE4066 message name +static constexpr uint16_t RTCM3_TYPE4067_MSGID = 4067; //!< RTCM3-TYPE4067 message ID +static constexpr const char* RTCM3_TYPE4067_STRID = "RTCM3-TYPE4067"; //!< RTCM3-TYPE4067 message name +static constexpr uint16_t RTCM3_TYPE4068_MSGID = 4068; //!< RTCM3-TYPE4068 message ID +static constexpr const char* RTCM3_TYPE4068_STRID = "RTCM3-TYPE4068"; //!< RTCM3-TYPE4068 message name +static constexpr uint16_t RTCM3_TYPE4069_MSGID = 4069; //!< RTCM3-TYPE4069 message ID +static constexpr const char* RTCM3_TYPE4069_STRID = "RTCM3-TYPE4069"; //!< RTCM3-TYPE4069 message name +static constexpr uint16_t RTCM3_TYPE4070_MSGID = 4070; //!< RTCM3-TYPE4070 message ID +static constexpr const char* RTCM3_TYPE4070_STRID = "RTCM3-TYPE4070"; //!< RTCM3-TYPE4070 message name +static constexpr uint16_t RTCM3_TYPE4071_MSGID = 4071; //!< RTCM3-TYPE4071 message ID +static constexpr const char* RTCM3_TYPE4071_STRID = "RTCM3-TYPE4071"; //!< RTCM3-TYPE4071 message name +static constexpr uint16_t RTCM3_TYPE4072_MSGID = 4072; //!< RTCM3-TYPE4072 message ID +static constexpr const char* RTCM3_TYPE4072_STRID = "RTCM3-TYPE4072"; //!< RTCM3-TYPE4072 message name +static constexpr uint16_t RTCM3_TYPE4073_MSGID = 4073; //!< RTCM3-TYPE4073 message ID +static constexpr const char* RTCM3_TYPE4073_STRID = "RTCM3-TYPE4073"; //!< RTCM3-TYPE4073 message name +static constexpr uint16_t RTCM3_TYPE4074_MSGID = 4074; //!< RTCM3-TYPE4074 message ID +static constexpr const char* RTCM3_TYPE4074_STRID = "RTCM3-TYPE4074"; //!< RTCM3-TYPE4074 message name +static constexpr uint16_t RTCM3_TYPE4075_MSGID = 4075; //!< RTCM3-TYPE4075 message ID +static constexpr const char* RTCM3_TYPE4075_STRID = "RTCM3-TYPE4075"; //!< RTCM3-TYPE4075 message name +static constexpr uint16_t RTCM3_TYPE4076_MSGID = 4076; //!< RTCM3-TYPE4076 message ID +static constexpr const char* RTCM3_TYPE4076_STRID = "RTCM3-TYPE4076"; //!< RTCM3-TYPE4076 message name +static constexpr uint16_t RTCM3_TYPE4077_MSGID = 4077; //!< RTCM3-TYPE4077 message ID +static constexpr const char* RTCM3_TYPE4077_STRID = "RTCM3-TYPE4077"; //!< RTCM3-TYPE4077 message name +static constexpr uint16_t RTCM3_TYPE4078_MSGID = 4078; //!< RTCM3-TYPE4078 message ID +static constexpr const char* RTCM3_TYPE4078_STRID = "RTCM3-TYPE4078"; //!< RTCM3-TYPE4078 message name +static constexpr uint16_t RTCM3_TYPE4079_MSGID = 4079; //!< RTCM3-TYPE4079 message ID +static constexpr const char* RTCM3_TYPE4079_STRID = "RTCM3-TYPE4079"; //!< RTCM3-TYPE4079 message name +static constexpr uint16_t RTCM3_TYPE4080_MSGID = 4080; //!< RTCM3-TYPE4080 message ID +static constexpr const char* RTCM3_TYPE4080_STRID = "RTCM3-TYPE4080"; //!< RTCM3-TYPE4080 message name +static constexpr uint16_t RTCM3_TYPE4081_MSGID = 4081; //!< RTCM3-TYPE4081 message ID +static constexpr const char* RTCM3_TYPE4081_STRID = "RTCM3-TYPE4081"; //!< RTCM3-TYPE4081 message name +static constexpr uint16_t RTCM3_TYPE4082_MSGID = 4082; //!< RTCM3-TYPE4082 message ID +static constexpr const char* RTCM3_TYPE4082_STRID = "RTCM3-TYPE4082"; //!< RTCM3-TYPE4082 message name +static constexpr uint16_t RTCM3_TYPE4083_MSGID = 4083; //!< RTCM3-TYPE4083 message ID +static constexpr const char* RTCM3_TYPE4083_STRID = "RTCM3-TYPE4083"; //!< RTCM3-TYPE4083 message name +static constexpr uint16_t RTCM3_TYPE4084_MSGID = 4084; //!< RTCM3-TYPE4084 message ID +static constexpr const char* RTCM3_TYPE4084_STRID = "RTCM3-TYPE4084"; //!< RTCM3-TYPE4084 message name +static constexpr uint16_t RTCM3_TYPE4085_MSGID = 4085; //!< RTCM3-TYPE4085 message ID +static constexpr const char* RTCM3_TYPE4085_STRID = "RTCM3-TYPE4085"; //!< RTCM3-TYPE4085 message name +static constexpr uint16_t RTCM3_TYPE4086_MSGID = 4086; //!< RTCM3-TYPE4086 message ID +static constexpr const char* RTCM3_TYPE4086_STRID = "RTCM3-TYPE4086"; //!< RTCM3-TYPE4086 message name +static constexpr uint16_t RTCM3_TYPE4087_MSGID = 4087; //!< RTCM3-TYPE4087 message ID +static constexpr const char* RTCM3_TYPE4087_STRID = "RTCM3-TYPE4087"; //!< RTCM3-TYPE4087 message name +static constexpr uint16_t RTCM3_TYPE4088_MSGID = 4088; //!< RTCM3-TYPE4088 message ID +static constexpr const char* RTCM3_TYPE4088_STRID = "RTCM3-TYPE4088"; //!< RTCM3-TYPE4088 message name +static constexpr uint16_t RTCM3_TYPE4089_MSGID = 4089; //!< RTCM3-TYPE4089 message ID +static constexpr const char* RTCM3_TYPE4089_STRID = "RTCM3-TYPE4089"; //!< RTCM3-TYPE4089 message name +static constexpr uint16_t RTCM3_TYPE4090_MSGID = 4090; //!< RTCM3-TYPE4090 message ID +static constexpr const char* RTCM3_TYPE4090_STRID = "RTCM3-TYPE4090"; //!< RTCM3-TYPE4090 message name +static constexpr uint16_t RTCM3_TYPE4091_MSGID = 4091; //!< RTCM3-TYPE4091 message ID +static constexpr const char* RTCM3_TYPE4091_STRID = "RTCM3-TYPE4091"; //!< RTCM3-TYPE4091 message name +static constexpr uint16_t RTCM3_TYPE4092_MSGID = 4092; //!< RTCM3-TYPE4092 message ID +static constexpr const char* RTCM3_TYPE4092_STRID = "RTCM3-TYPE4092"; //!< RTCM3-TYPE4092 message name +static constexpr uint16_t RTCM3_TYPE4093_MSGID = 4093; //!< RTCM3-TYPE4093 message ID +static constexpr const char* RTCM3_TYPE4093_STRID = "RTCM3-TYPE4093"; //!< RTCM3-TYPE4093 message name +static constexpr uint16_t RTCM3_TYPE4094_MSGID = 4094; //!< RTCM3-TYPE4094 message ID +static constexpr const char* RTCM3_TYPE4094_STRID = "RTCM3-TYPE4094"; //!< RTCM3-TYPE4094 message name +static constexpr uint16_t RTCM3_TYPE4095_MSGID = 4095; //!< RTCM3-TYPE4095 message ID +static constexpr const char* RTCM3_TYPE4095_STRID = "RTCM3-TYPE4095"; //!< RTCM3-TYPE4095 message name +static constexpr uint16_t RTCM3_TYPE4072_0_SUBID = 0; //!< RTCM3-TYPE4072_0 message ID +static constexpr const char* RTCM3_TYPE4072_0_STRID = "RTCM3-TYPE4072_0"; //!< RTCM3-TYPE4072_0 message name +static constexpr uint16_t RTCM3_TYPE4072_1_SUBID = 1; //!< RTCM3-TYPE4072_1 message ID +static constexpr const char* RTCM3_TYPE4072_1_STRID = "RTCM3-TYPE4072_1"; //!< RTCM3-TYPE4072_1 message name +// @fp_codegen_end{FPSDK_COMMON_PARSER_RTCM3_MESSAGES} +// clang-format on + +///@} + +/* ****************************************************************************************************************** */ +} // namespace rtcm3 +} // namespace parser +} // namespace common +} // namespace fpsdk +#endif // __FPSDK_COMMON_PARSER_RTCM3_HPP__ diff --git a/fpsdk_common/include/fpsdk_common/parser/spartn.hpp b/fpsdk_common/include/fpsdk_common/parser/spartn.hpp new file mode 100644 index 0000000..62617e3 --- /dev/null +++ b/fpsdk_common/include/fpsdk_common/parser/spartn.hpp @@ -0,0 +1,179 @@ +/** + * \verbatim + * ___ ___ + * \ \ / / + * \ \/ / Copyright (c) Fixposition AG (www.fixposition.com) and contributors + * / /\ \ License: see the LICENSE file + * /__/ \__\ + * + * Based on work by flipflip (https://github.com/phkehl) + * The information on message structures, IDs, descriptions etc. in this file are from publicly available data, such as: + * - Secure Position Augmentation for Real-Time Navigation (SPARTN) Interface Control Document + * (https://www.spartnformat.org) + * \endverbatim + * + * @file + * @brief Fixposition SDK: Parser SPARTN routines and types + * + * @page FPSDK_COMMON_PARSER_SPARTN Parser SPARTN routines and types + * + * **API**: fpsdk_common/parser/spartn.hpp and fpsdk::common::parser::spartn + * + */ +#ifndef __FPSDK_COMMON_PARSER_SPARTN_HPP__ +#define __FPSDK_COMMON_PARSER_SPARTN_HPP__ + +/* LIBC/STL */ +#include + +/* EXTERNAL */ + +/* PACKAGE */ + +namespace fpsdk { +namespace common { +namespace parser { +/** + * @brief Parser SPARTN routines and types + */ +namespace spartn { +/* ****************************************************************************************************************** */ + +static constexpr uint8_t SPARTN_PREAMBLE = 0x73; //!< SPARTN protocol preamble +static constexpr std::size_t SPARTN_MIN_HEAD_SIZE = 8; //!< Minimal header size of a SPARTN message + +/** + * @brief Get SPARTN message type + * + * @param[in] msg Pointer to the start of the message + * + * @note No check on the data provided is done. The caller must ensure that the data is a valid SPARTN message. + * + * @returns the SPARTN message type + */ +constexpr uint8_t SpartnType(const uint8_t* msg) +{ + return (msg[1] & 0xfe) >> 1; +} + +/** + * @brief Get SPARTN message sub-type + * + * @param[in] msg Pointer to the start of the message + * + * @note No check on the data provided is done. The caller must ensure that the data is a valid SPARTN message. + * + * @returns the SPARTN message sub-type + */ +constexpr uint8_t SpartnSubType(const uint8_t* msg) +{ + return (msg[4] & 0xf0) >> 4; +} + +/** + * @brief Get SPARTN message name + * + * Generates a name (string) in the form "SPARTN-TYPEN_S", where N is the message type and S is the sub-type. For + * example: "SPARTN-TYPE1_2". + * + * @param[out] name String to write the name to + * @param[in] size Size of \c name (incl. nul termination) + * @param[in] msg Pointer to the SPARTN message + * @param[in] msg_size Size of the \c msg + * + * @note No check on the data provided is done. The caller must ensure that the data is a valid SPARTN message. + * + * @returns true if message name was generated, false if \c name buffer was too small + */ +bool SpartnGetMessageName(char* name, const std::size_t size, const uint8_t* msg, const std::size_t msg_size); + +/** + * @brief Get SPARTN message info + * + * This stringifies the content of some SPARTN messages, for debugging. + * + * @param[out] info String to write the info to + * @param[in] size Size of \c name (incl. nul termination) + * @param[in] msg Pointer to the SPARTN message + * @param[in] msg_size Size of the \c msg + * + * @note No check on the data provided is done. The caller must ensure that the data is a valid SPARTN message. + * + * @returns true if message info was generated (even if info is empty), false if \c name buffer was too small + */ +bool SpartnGetMessageInfo(char* info, const std::size_t size, const uint8_t* msg, const std::size_t msg_size); + +/** + * @brief Get description for a SPARTN message type + * + * @param[in] type Message type + * @param[in] subtype Message sub-type (if appropriate) + * + * @return the description of the message type, if available, NULL otherwise + */ +const char* SpartnGetTypeDesc(const uint16_t type, const uint16_t subtype = 0xffff); + +/** + * @name SPARTN messages (names and IDs) + * + * @{ + */ +// clang-format off +// @fp_codegen_begin{FPSDK_COMMON_PARSER_SPARTN_MESSAGES} +static constexpr uint16_t SPARTN_OCB_MSGID = 0; //!< SPARTN-OCB message ID +static constexpr const char* SPARTN_OCB_STRID = "SPARTN-OCB"; //!< SPARTN-OCB message name +static constexpr uint16_t SPARTN_HPAC_MSGID = 1; //!< SPARTN-HPAC message ID +static constexpr const char* SPARTN_HPAC_STRID = "SPARTN-HPAC"; //!< SPARTN-HPAC message name +static constexpr uint16_t SPARTN_GAD_MSGID = 2; //!< SPARTN-GAD message ID +static constexpr const char* SPARTN_GAD_STRID = "SPARTN-GAD"; //!< SPARTN-GAD message name +static constexpr uint16_t SPARTN_BPAC_MSGID = 3; //!< SPARTN-BPAC message ID +static constexpr const char* SPARTN_BPAC_STRID = "SPARTN-BPAC"; //!< SPARTN-BPAC message name +static constexpr uint16_t SPARTN_EAS_MSGID = 4; //!< SPARTN-EAS message ID +static constexpr const char* SPARTN_EAS_STRID = "SPARTN-EAS"; //!< SPARTN-EAS message name +static constexpr uint16_t SPARTN_PROP_MSGID = 120; //!< SPARTN-PROP message ID +static constexpr const char* SPARTN_PROP_STRID = "SPARTN-PROP"; //!< SPARTN-PROP message name +static constexpr uint16_t SPARTN_OCB_GPS_SUBID = 0; //!< SPARTN-OCB-GPS message ID +static constexpr const char* SPARTN_OCB_GPS_STRID = "SPARTN-OCB-GPS"; //!< SPARTN-OCB-GPS message name +static constexpr uint16_t SPARTN_OCB_GLO_SUBID = 1; //!< SPARTN-OCB-GLO message ID +static constexpr const char* SPARTN_OCB_GLO_STRID = "SPARTN-OCB-GLO"; //!< SPARTN-OCB-GLO message name +static constexpr uint16_t SPARTN_OCB_GAL_SUBID = 2; //!< SPARTN-OCB-GAL message ID +static constexpr const char* SPARTN_OCB_GAL_STRID = "SPARTN-OCB-GAL"; //!< SPARTN-OCB-GAL message name +static constexpr uint16_t SPARTN_OCB_BDS_SUBID = 3; //!< SPARTN-OCB-BDS message ID +static constexpr const char* SPARTN_OCB_BDS_STRID = "SPARTN-OCB-BDS"; //!< SPARTN-OCB-BDS message name +static constexpr uint16_t SPARTN_OCB_QZSS_SUBID = 4; //!< SPARTN-OCB-QZSS message ID +static constexpr const char* SPARTN_OCB_QZSS_STRID = "SPARTN-OCB-QZSS"; //!< SPARTN-OCB-QZSS message name +static constexpr uint16_t SPARTN_HPAC_GPS_SUBID = 0; //!< SPARTN-HPAC-GPS message ID +static constexpr const char* SPARTN_HPAC_GPS_STRID = "SPARTN-HPAC-GPS"; //!< SPARTN-HPAC-GPS message name +static constexpr uint16_t SPARTN_HPAC_GLO_SUBID = 1; //!< SPARTN-HPAC-GLO message ID +static constexpr const char* SPARTN_HPAC_GLO_STRID = "SPARTN-HPAC-GLO"; //!< SPARTN-HPAC-GLO message name +static constexpr uint16_t SPARTN_HPAC_GAL_SUBID = 2; //!< SPARTN-HPAC-GAL message ID +static constexpr const char* SPARTN_HPAC_GAL_STRID = "SPARTN-HPAC-GAL"; //!< SPARTN-HPAC-GAL message name +static constexpr uint16_t SPARTN_HPAC_BDS_SUBID = 3; //!< SPARTN-HPAC-BDS message ID +static constexpr const char* SPARTN_HPAC_BDS_STRID = "SPARTN-HPAC-BDS"; //!< SPARTN-HPAC-BDS message name +static constexpr uint16_t SPARTN_HPAC_QZSS_SUBID = 4; //!< SPARTN-HPAC-QZSS message ID +static constexpr const char* SPARTN_HPAC_QZSS_STRID = "SPARTN-HPAC-QZSS"; //!< SPARTN-HPAC-QZSS message name +static constexpr uint16_t SPARTN_GAD_GAD_SUBID = 0; //!< SPARTN-GAD-GAD message ID +static constexpr const char* SPARTN_GAD_GAD_STRID = "SPARTN-GAD-GAD"; //!< SPARTN-GAD-GAD message name +static constexpr uint16_t SPARTN_BPAC_POLY_SUBID = 0; //!< SPARTN-BPAC-POLY message ID +static constexpr const char* SPARTN_BPAC_POLY_STRID = "SPARTN-BPAC-POLY"; //!< SPARTN-BPAC-POLY message name +static constexpr uint16_t SPARTN_EAS_KEY_SUBID = 0; //!< SPARTN-EAS-KEY message ID +static constexpr const char* SPARTN_EAS_KEY_STRID = "SPARTN-EAS-KEY"; //!< SPARTN-EAS-KEY message name +static constexpr uint16_t SPARTN_EAS_GROUP_SUBID = 1; //!< SPARTN-EAS-GROUP message ID +static constexpr const char* SPARTN_EAS_GROUP_STRID = "SPARTN-EAS-GROUP"; //!< SPARTN-EAS-GROUP message name +static constexpr uint16_t SPARTN_PROP_EST_SUBID = 0; //!< SPARTN-PROP-EST message ID +static constexpr const char* SPARTN_PROP_EST_STRID = "SPARTN-PROP-EST"; //!< SPARTN-PROP-EST message name +static constexpr uint16_t SPARTN_PROP_UBLOX_SUBID = 1; //!< SPARTN-PROP-UBLOX message ID +static constexpr const char* SPARTN_PROP_UBLOX_STRID = "SPARTN-PROP-UBLOX"; //!< SPARTN-PROP-UBLOX message name +static constexpr uint16_t SPARTN_PROP_SWIFT_SUBID = 2; //!< SPARTN-PROP-SWIFT message ID +static constexpr const char* SPARTN_PROP_SWIFT_STRID = "SPARTN-PROP-SWIFT"; //!< SPARTN-PROP-SWIFT message name +// @fp_codegen_end{FPSDK_COMMON_PARSER_SPARTN_MESSAGES} +// clang-format on + +///@} + +/* ****************************************************************************************************************** */ +} // namespace spartn +} // namespace parser +} // namespace common +} // namespace fpsdk +#endif // __FPSDK_COMMON_PARSER_SPARTN_HPP__ diff --git a/fpsdk_common/include/fpsdk_common/parser/types.hpp b/fpsdk_common/include/fpsdk_common/parser/types.hpp new file mode 100644 index 0000000..ef63053 --- /dev/null +++ b/fpsdk_common/include/fpsdk_common/parser/types.hpp @@ -0,0 +1,178 @@ +/** + * \verbatim + * ___ ___ + * \ \ / / + * \ \/ / Copyright (c) Fixposition AG (www.fixposition.com) and contributors + * / /\ \ License: see the LICENSE file + * /__/ \__\ + * + * Based on work by flipflip (https://github.com/phkehl) + * \endverbatim + * + * @file + * @brief Fixposition SDK: Parser + * + * @page FPSDK_COMMON_PARSER_TYPES Parser common types + * + * **API**: fpsdk_common/parser/types.hpp and fpsdk::common::parser + * + */ +#ifndef __FPSDK_COMMON_PARSER_TYPES_HPP__ +#define __FPSDK_COMMON_PARSER_TYPES_HPP__ + +/* LIBC/STL */ +#include +#include +#include +#include + +/* EXTERNAL */ + +/* PACKAGE */ + +namespace fpsdk { +namespace common { +namespace parser { +/* ****************************************************************************************************************** */ + +/** + * @brief Protocols (message types), see also @ref FPSDK_COMMON_PARSER_NAMING + */ +enum class Protocol : int +{ + // See FP_PARSER_NAMEING for naming constraints! + FP_A = 1, //!< FP_A (Fixposition proprietary ASCII) (#PROTOCOL_NAME_FP_A) + FP_B, //!< FP_B (Fixposition proprietary binary) (#PROTOCOL_NAME_FP_B) + NMEA, //!< NMEA (#PROTOCOL_NAME_NMEA) + UBX, //!< UBX (u-blox proprietary binary) (#PROTOCOL_NAME_UBX) + RTCM3, //!< RTCM3 (#PROTOCOL_NAME_RTCM3) + UNI_B, //!< UNI_B (Unicore proprietary binary) (#PROTOCOL_NAME_UNI_B) + NOV_B, //!< NOV_B (NovAtel proprietary binary, long or short header) (#PROTOCOL_NAME_NOV_B) + SPARTN, //!< SPARTN (#PROTOCOL_NAME_SPARTN) + OTHER, //!< Other "message" (unknown or corrupt message, spurious data, line noise, ...) (#PROTOCOL_NAME_OTHER) +}; + +/** + * @name Protocol names + * @{ + */ +// clang-format off + // See FP_PARSER_NAMEING for naming constraints! +static constexpr const char* PROTOCOL_NAME_FP_A = "FP_A"; //!< Name (label) for Protocol::FP_A +static constexpr const char* PROTOCOL_NAME_FP_B = "FP_B"; //!< Name (label) for Protocol::FP_B +static constexpr const char* PROTOCOL_NAME_NMEA = "NMEA"; //!< Name (label) for Protocol::NMEA +static constexpr const char* PROTOCOL_NAME_UBX = "UBX"; //!< Name (label) for Protocol::UBX +static constexpr const char* PROTOCOL_NAME_RTCM3 = "RTCM3"; //!< Name (label) for Protocol::RTCM3 +static constexpr const char* PROTOCOL_NAME_UNI_B = "UNI_B"; //!< Name (label) for Protocol::UNI_B +static constexpr const char* PROTOCOL_NAME_NOV_B = "NOV_B"; //!< Name (label) for Protocol::NOV_B +static constexpr const char* PROTOCOL_NAME_SPARTN = "SPARTN"; //!< Name (label) for Protocol::SPARTN +static constexpr const char* PROTOCOL_NAME_OTHER = "OTHER"; //!< Name (label) for Protocol::OTHER +// clang-format on +///@} + +/** + * @brief Stringify Protocol + * + * @param[in] proto The protocol + * + * @returns a unique string for the type, for example "UBX" (PROTOCOL_NAME_UBX) for Protocol::UBX + */ +const char* ProtocolStr(const Protocol proto); + +/** + * @brief Get Protocol from name + * + * @param[in] name The protocol name + * + * @returns the Protocol enum, for example Protocol::UBX for "UBX" (PROTOCOL_NAME_UBX), and for any unknown string + * Protocol::OTHER + */ +Protocol StrProtocol(const char* name); + +/** + * @brief Message frame output by the Parser + */ +struct ParserMsg +{ + // clang-format off + Protocol proto_ = Protocol::OTHER; //!< Protocol (message type) + std::vector data_; //!< Message data + std::string name_; //!< Name of the message + mutable std::string info_; //!< Message (debug) info, default empty, call MakeInfo() to fill + uint64_t seq_ = 0; //!< Message counter (starting at 1) + // clang-formt on + + /** + * @brief Make info_ field + * + * Fills the info field, unless it's not empty. Depending on the message, this may or may not put something + * useful into the info_ field. + */ + void MakeInfo() const; +}; + +/** + * @brief Parser statistics + */ +struct ParserStats { + uint64_t n_msgs_ = 0; //!< Number of messages parsed + uint64_t s_msgs_ = 0; //!< Total size of messages parsed + uint64_t n_fpa_ = 0; //!< Number of Protocol::FP_A messages + uint64_t s_fpa_ = 0; //!< Total size of Protocol::FP_A messages + uint64_t n_fpb_ = 0; //!< Number of Protocol::FP_B messages + uint64_t s_fpb_ = 0; //!< Total size of Protocol::FP_B messages + uint64_t n_nmea_ = 0; //!< Number of Protocol::NMEA messages + uint64_t s_nmea_ = 0; //!< Total size of Protocol::NMEA messages + uint64_t n_ubx_ = 0; //!< Number of Protocol::UBX messages + uint64_t s_ubx_ = 0; //!< Total size of Protocol::UBX messages + uint64_t n_rtcm3_ = 0; //!< Number of Protocol::RTCM3 messages + uint64_t s_rtcm3_ = 0; //!< Total size of Protocol::RTCM3 messages + uint64_t n_unib_ = 0; //!< Number of Protocol::UNI_B messages + uint64_t s_unib_ = 0; //!< Total size of Protocol::UNI_B messages + uint64_t n_novb_ = 0; //!< Number of Protocol::NOV_B messages + uint64_t s_novb_ = 0; //!< Total size of Protocol::NOV_B messages + uint64_t n_spartn_ = 0; //!< Number of Protocol::SPARTN messages + uint64_t s_spartn_ = 0; //!< Total size of Protocol::SPARTN messages + uint64_t n_other_ = 0; //!< Number of Protocol::OTHER messages + uint64_t s_other_ = 0; //!< Total size of Protocol::OTHER messages +}; + +/** + * @name Parser constraints + * @{ + */ +// clang-format off +static constexpr std::size_t MAX_ADD_SIZE = 32 * 1024; //!< Max size for Parser::Add() that is guaranteed to work +static constexpr std::size_t MAX_NAME_SIZE = 100; //!< Maximum size of message name string (incl. nul termination) +static constexpr std::size_t MAX_INFO_SIZE = 200; //!< Maximum size of message info string (incl. nul termination) +static constexpr std::size_t MAX_FP_A_SIZE = 400; //!< Maximum FP_A message size (must be the same as MAX_NMEA_SIZE) +static constexpr std::size_t MAX_FP_B_SIZE = 4096; //!< Maximum FP_B message size +static constexpr std::size_t MAX_NMEA_SIZE = 400; //!< Maximum NMEA message size (standard NMEA would be 82!) +static constexpr std::size_t MAX_UBX_SIZE = 4096; //!< Maximum UBX message size +static constexpr std::size_t MAX_RTCM3_SIZE = 1028; //!< Maximum RTCM3 message size +static constexpr std::size_t MAX_SPARTN_SIZE = 1110; //!< Maximum SPARTN message size +static constexpr std::size_t MAX_NOV_B_SIZE = 4096; //!< Maximum NOV_B message size +static constexpr std::size_t MAX_UNI_B_SIZE = 4096; //!< Maximum UNI_B message size +static constexpr std::size_t MAX_OTHER_SIZE = 256; //!< Maximum OTHER message size +static constexpr std::size_t MAX_ANY_SIZE = std::max({ MAX_NMEA_SIZE, MAX_FP_A_SIZE, MAX_FP_B_SIZE, MAX_UBX_SIZE, + MAX_RTCM3_SIZE, MAX_SPARTN_SIZE, MAX_NOV_B_SIZE, MAX_UNI_B_SIZE, MAX_OTHER_SIZE }); //!< The largest of the above +static constexpr std::size_t MIN_ANY_SIZE = std::min({ MAX_NMEA_SIZE, MAX_FP_A_SIZE, MAX_FP_B_SIZE, MAX_UBX_SIZE, + MAX_RTCM3_SIZE, MAX_SPARTN_SIZE, MAX_NOV_B_SIZE, MAX_UNI_B_SIZE, MAX_OTHER_SIZE }); //!< The smallest of the above +// clang-format on +///@} + +// Assertions on some constraints we rely on +static_assert(MAX_ADD_SIZE > (4 * MAX_ANY_SIZE), ""); // Should be fairly large... +static_assert(MAX_NMEA_SIZE == MAX_FP_A_SIZE, ""); // As documented above +static_assert(MIN_ANY_SIZE >= 256, ""); // Something reasonable... +static_assert(MIN_ANY_SIZE < 1024, ""); // Something reasonable... +static_assert(MAX_ANY_SIZE >= 2048, ""); // Something reasonable... +static_assert(MAX_ANY_SIZE <= 10240, ""); // Something reasonable... +static_assert(MAX_RTCM3_SIZE < (0x3ff + 6), ""); // 10-bits payload size + frame size +static_assert(MAX_SPARTN_SIZE < (0x3ff + 88), ""); // 10-bits payload size + max. frame size + +/* ****************************************************************************************************************** */ +} // namespace parser +} // namespace common +} // namespace fpsdk +#endif // __FPSDK_COMMON_PARSER_TYPES_HPP__ diff --git a/fpsdk_common/include/fpsdk_common/parser/ubx.hpp b/fpsdk_common/include/fpsdk_common/parser/ubx.hpp new file mode 100644 index 0000000..bbefbaa --- /dev/null +++ b/fpsdk_common/include/fpsdk_common/parser/ubx.hpp @@ -0,0 +1,2598 @@ +// clang-format off +/** + * \verbatim + * ___ ___ + * \ \ / / + * \ \/ / Copyright (c) Fixposition AG (www.fixposition.com) and contributors + * / /\ \ License: see the LICENSE file + * /__/ \__\ + * + * Based on work by flipflip (https://github.com/phkehl) + * The information on message structures, IDs, descriptions etc. in this file are from publicly available data, such as: + * - u-blox ZED-F9P Interface Description (HPG 1.50) (https://www.u-blox.com/en/docs/UBXDOC-963802114-12815), copyright (c) 2024 u-blox AG + * - u-blox ZED-F9T Interface Description (R02) (https://www.u-blox.com/en/docs/UBX-19003606), copyright (c) 2020 u-blox AG + * - u-blox NEO-M9N Interface description (SPG 4.04) (https://www.u-blox.com/en/docs/UBX-19035940), copyright (c) 2020 u-blox AG + * - u-blox ZED-F9R Interface description (HPS 1.20) (https://www.u-blox.com/en/docs/UBX-19056845), copyright (c) 2020 u-blox AG + * - u-blox F9 HPS 1.21 Interface Description (ZEF-F9R) (https://www.u-blox.com/en/docs/UBX-21019746), copyright (c) 2021 u-blox AG + * - u-center 20.01, copyright (c) 2020 u-blox AG + * \endverbatim + * + * @file + * @brief Fixposition SDK: Parser UBX routines and types + * + * @page FPSDK_COMMON_PARSER_UBX Parser UBX routines and types + * + * **API**: fpsdk_common/parser/ubx.hpp and fpsdk::common::parser::ubx + * + */ +// clang-format on +#ifndef __FPSDK_COMMON_PARSER_UBX_HPP__ +#define __FPSDK_COMMON_PARSER_UBX_HPP__ + +/* LIBC/STL */ +#include +#include +#include +#include + +/* EXTERNAL */ + +/* PACKAGE */ + +namespace fpsdk { +namespace common { +namespace parser { +/** + * @brief Parser UBX routines and types + */ +namespace ubx { +/* ****************************************************************************************************************** */ + +// Doxygen is easily confused.. :-/ +//! Message truct that must be packed +#ifndef _DOXYGEN_ +# define UBX_PACKED __attribute__((packed)) +#else +# define UBX_PACKED /* packed */ +#endif + +static constexpr std::size_t UBX_FRAME_SIZE = 8; //!< Size (in bytes) of UBX frame +static constexpr std::size_t UBX_HEAD_SIZE = 6; //!< Size of UBX frame header +static constexpr uint8_t UBX_SYNC_1 = 0xb5; //!< UBX frame sync char 1 +static constexpr uint8_t UBX_SYNC_2 = 0x62; //!< UBX frame sync char 2 + +/** + * @brief Get class ID from message + * + * @param[in] msg Pointer to the start of the message + * + * @note No check on the data provided is done. This is meant for use as a helper in other functions. Checks on the + * \c msg and its data should be carried out there. + * + * @returns the UBX class ID + */ +constexpr uint8_t UbxClsId(const uint8_t* msg) +{ + return (((uint8_t*)(msg))[2]); +} + +/** + * @brief Get message ID from message + * + * @param[in] msg Pointer to the start of the message + * + * @note No check on the data provided is done. This is meant for use as a helper in other functions. Checks on the + * \c msg and its data should be carried out there. + * + * @returns the UBX message ID + */ +constexpr uint8_t UbxMsgId(const uint8_t* msg) +{ + return (((uint8_t*)(msg))[3]); +} + +/** + * @brief Get UBX message name + * + * Generates a name (string) in the form "UBX-CLSID-MSGID", where CLSID and MSGID are suitable stringifications of the + * class ID and message ID if known (for example, "UBX-NAV-PVT", respectively %02X formatted IDs if unknown (for + * example, "UBX-NAV-F4" or "UBX-A0-B1"). + * + * @param[out] name String to write the name to + * @param[in] size Size of \c name (incl. nul termination) + * @param[in] msg Pointer to the UBX message + * @param[in] msg_size Size of the \c msg + * + * @note No check on the data provided is done. The caller must ensure that the data is a valid UBX message. + * + * @returns true if message name was generated, false if \c name buffer was too small + */ +bool UbxGetMessageName(char* name, const std::size_t size, const uint8_t* msg, const std::size_t msg_size); + +/** + * @brief Get UBX message info + * + * This stringifies the content of some UBX messages, for debugging. + * + * @param[out] info String to write the info to + * @param[in] size Size of \c name (incl. nul termination) + * @param[in] msg Pointer to the UBX message + * @param[in] msg_size Size of the \c msg + * + * @note No check on the data provided is done. The caller must ensure that the data is a valid UBX message. + * + * @returns true if message info was generated (even if info is empty), false if \c name buffer was too small + */ +bool UbxGetMessageInfo(char* info, const std::size_t size, const uint8_t* msg, const std::size_t msg_size); + +/** + * @brief Make a UBX message + * + * @param[out] msg The message frame + * @param[in] cls_id Class ID + * @param[in] msg_id Message ID + * @param[in] payload The message payload (up to MAX_UBX_SIZE - UBX_FRAME_SIZE bytes, can be empty) + * + * @returns true if the message was created successfully + * + * @returns true if the message was successfully constructed (\c msg now contains the message), + * false if failed contructing the message (payload too large) + */ +bool UbxMakeMessage( + std::vector& msg, const uint8_t cls_id, const uint8_t msg_id, const std::vector& payload); + +/** + * @brief Make a UBX message + * + * @param[out] msg The message frame + * @param[in] cls_id Class ID + * @param[in] msg_id Message ID + * @param[in] payload The message payload (up to MAX_UBX_SIZE - UBX_FRAME_SIZE bytes, can be NULL) + * @param[in] payload_size Size of the payload (up to MAX_UBX_SIZE - UBX_FRAME_SIZE, can be 0, even if payload is not + * NULL) + * + * @returns true if the message was successfully constructed (\c msg now contains the message), + * false if failed contructing the message (payload too large, bad arguments) + */ +bool UbxMakeMessage(std::vector& msg, const uint8_t cls_id, const uint8_t msg_id, const uint8_t* payload, + const std::size_t payload_size); + +/** + * @brief Stringify UBX-RXM-SFRBX, for debugging + * + * @param[out] info String to format + * @param[in] size Maximum size of string (incl. nul termination) + * @param[in] msg The UBX-RXM-SFRBX message + * @param[in] msg_size Size of the UBX-RXM-SFRBX message + * + * @returns the length of the string generated (excl. nul termination) + */ +std::size_t UbxRxmSfrbxInfo(char* info, const std::size_t size, const uint8_t* msg, const std::size_t msg_size); + +/** + * @brief Stringify UBX-MON-VER message (software version and module name) + * + * @param[out] str String to format + * @param[in] size Maximum size of string (incl. nul termination) + * @param[in] msg The UBX-RXM-SFRBX message + * @param[in] msg_size Size of the UBX-RXM-SFRBX message + * + * @returns the length of the string generated (excl. nul termination) + */ +std::size_t UbxMonVerToVerStr(char* str, const std::size_t size, const uint8_t* msg, const std::size_t msg_size); + +/** + * @name UBX classes and messages (names and IDs) + * + * @{ + */ +// clang-format off +// @fp_codegen_begin{FPSDK_COMMON_PARSER_UBX_CLASSES} +static constexpr uint16_t UBX_ACK_CLSID = 0x05; //!< UBX-ACK class ID +static constexpr const char* UBX_ACK_STRID = "UBX-ACK"; //!< UBX-ACK class name +static constexpr uint16_t UBX_CFG_CLSID = 0x06; //!< UBX-CFG class ID +static constexpr const char* UBX_CFG_STRID = "UBX-CFG"; //!< UBX-CFG class name +static constexpr uint16_t UBX_ESF_CLSID = 0x10; //!< UBX-ESF class ID +static constexpr const char* UBX_ESF_STRID = "UBX-ESF"; //!< UBX-ESF class name +static constexpr uint16_t UBX_INF_CLSID = 0x04; //!< UBX-INF class ID +static constexpr const char* UBX_INF_STRID = "UBX-INF"; //!< UBX-INF class name +static constexpr uint16_t UBX_LOG_CLSID = 0x21; //!< UBX-LOG class ID +static constexpr const char* UBX_LOG_STRID = "UBX-LOG"; //!< UBX-LOG class name +static constexpr uint16_t UBX_MGA_CLSID = 0x13; //!< UBX-MGA class ID +static constexpr const char* UBX_MGA_STRID = "UBX-MGA"; //!< UBX-MGA class name +static constexpr uint16_t UBX_MON_CLSID = 0x0a; //!< UBX-MON class ID +static constexpr const char* UBX_MON_STRID = "UBX-MON"; //!< UBX-MON class name +static constexpr uint16_t UBX_NAV_CLSID = 0x01; //!< UBX-NAV class ID +static constexpr const char* UBX_NAV_STRID = "UBX-NAV"; //!< UBX-NAV class name +static constexpr uint16_t UBX_NAV2_CLSID = 0x29; //!< UBX-NAV2 class ID +static constexpr const char* UBX_NAV2_STRID = "UBX-NAV2"; //!< UBX-NAV2 class name +static constexpr uint16_t UBX_RXM_CLSID = 0x02; //!< UBX-RXM class ID +static constexpr const char* UBX_RXM_STRID = "UBX-RXM"; //!< UBX-RXM class name +static constexpr uint16_t UBX_SEC_CLSID = 0x27; //!< UBX-SEC class ID +static constexpr const char* UBX_SEC_STRID = "UBX-SEC"; //!< UBX-SEC class name +static constexpr uint16_t UBX_TIM_CLSID = 0x0d; //!< UBX-TIM class ID +static constexpr const char* UBX_TIM_STRID = "UBX-TIM"; //!< UBX-TIM class name +static constexpr uint16_t UBX_UPD_CLSID = 0x09; //!< UBX-UPD class ID +static constexpr const char* UBX_UPD_STRID = "UBX-UPD"; //!< UBX-UPD class name +static constexpr uint16_t UBX_NMEA_CLSID = 0xf0; //!< UBX-NMEA class ID +static constexpr const char* UBX_NMEA_STRID = "UBX-NMEA"; //!< UBX-NMEA class name +static constexpr uint16_t UBX_RTCM3_CLSID = 0xf5; //!< UBX-RTCM3 class ID +static constexpr const char* UBX_RTCM3_STRID = "UBX-RTCM3"; //!< UBX-RTCM3 class name +// @fp_codegen_end{FPSDK_COMMON_PARSER_UBX_CLASSES} +// clang-format on + +// clang-format off +// @fp_codegen_begin{FPSDK_COMMON_PARSER_UBX_MESSAGES} +static constexpr uint16_t UBX_ACK_ACK_MSGID = 0x01; //!< UBX-ACK-ACK message ID +static constexpr const char* UBX_ACK_ACK_STRID = "UBX-ACK-ACK"; //!< UBX-ACK-ACK message name +static constexpr uint16_t UBX_ACK_NAK_MSGID = 0x00; //!< UBX-ACK-NAK message ID +static constexpr const char* UBX_ACK_NAK_STRID = "UBX-ACK-NAK"; //!< UBX-ACK-NAK message name +static constexpr uint16_t UBX_CFG_CFG_MSGID = 0x09; //!< UBX-CFG-CFG message ID +static constexpr const char* UBX_CFG_CFG_STRID = "UBX-CFG-CFG"; //!< UBX-CFG-CFG message name +static constexpr uint16_t UBX_CFG_PWR_MSGID = 0x57; //!< UBX-CFG-PWR message ID +static constexpr const char* UBX_CFG_PWR_STRID = "UBX-CFG-PWR"; //!< UBX-CFG-PWR message name +static constexpr uint16_t UBX_CFG_RST_MSGID = 0x04; //!< UBX-CFG-RST message ID +static constexpr const char* UBX_CFG_RST_STRID = "UBX-CFG-RST"; //!< UBX-CFG-RST message name +static constexpr uint16_t UBX_CFG_VALDEL_MSGID = 0x8c; //!< UBX-CFG-VALDEL message ID +static constexpr const char* UBX_CFG_VALDEL_STRID = "UBX-CFG-VALDEL"; //!< UBX-CFG-VALDEL message name +static constexpr uint16_t UBX_CFG_VALGET_MSGID = 0x8b; //!< UBX-CFG-VALGET message ID +static constexpr const char* UBX_CFG_VALGET_STRID = "UBX-CFG-VALGET"; //!< UBX-CFG-VALGET message name +static constexpr uint16_t UBX_CFG_VALSET_MSGID = 0x8a; //!< UBX-CFG-VALSET message ID +static constexpr const char* UBX_CFG_VALSET_STRID = "UBX-CFG-VALSET"; //!< UBX-CFG-VALSET message name +static constexpr uint16_t UBX_ESF_ALG_MSGID = 0x14; //!< UBX-ESF-ALG message ID +static constexpr const char* UBX_ESF_ALG_STRID = "UBX-ESF-ALG"; //!< UBX-ESF-ALG message name +static constexpr uint16_t UBX_ESF_INS_MSGID = 0x15; //!< UBX-ESF-INS message ID +static constexpr const char* UBX_ESF_INS_STRID = "UBX-ESF-INS"; //!< UBX-ESF-INS message name +static constexpr uint16_t UBX_ESF_MEAS_MSGID = 0x02; //!< UBX-ESF-MEAS message ID +static constexpr const char* UBX_ESF_MEAS_STRID = "UBX-ESF-MEAS"; //!< UBX-ESF-MEAS message name +static constexpr uint16_t UBX_ESF_RAW_MSGID = 0x03; //!< UBX-ESF-RAW message ID +static constexpr const char* UBX_ESF_RAW_STRID = "UBX-ESF-RAW"; //!< UBX-ESF-RAW message name +static constexpr uint16_t UBX_ESF_STATUS_MSGID = 0x10; //!< UBX-ESF-STATUS message ID +static constexpr const char* UBX_ESF_STATUS_STRID = "UBX-ESF-STATUS"; //!< UBX-ESF-STATUS message name +static constexpr uint16_t UBX_INF_DEBUG_MSGID = 0x04; //!< UBX-INF-DEBUG message ID +static constexpr const char* UBX_INF_DEBUG_STRID = "UBX-INF-DEBUG"; //!< UBX-INF-DEBUG message name +static constexpr uint16_t UBX_INF_ERROR_MSGID = 0x00; //!< UBX-INF-ERROR message ID +static constexpr const char* UBX_INF_ERROR_STRID = "UBX-INF-ERROR"; //!< UBX-INF-ERROR message name +static constexpr uint16_t UBX_INF_NOTICE_MSGID = 0x02; //!< UBX-INF-NOTICE message ID +static constexpr const char* UBX_INF_NOTICE_STRID = "UBX-INF-NOTICE"; //!< UBX-INF-NOTICE message name +static constexpr uint16_t UBX_INF_TEST_MSGID = 0x03; //!< UBX-INF-TEST message ID +static constexpr const char* UBX_INF_TEST_STRID = "UBX-INF-TEST"; //!< UBX-INF-TEST message name +static constexpr uint16_t UBX_INF_WARNING_MSGID = 0x01; //!< UBX-INF-WARNING message ID +static constexpr const char* UBX_INF_WARNING_STRID = "UBX-INF-WARNING"; //!< UBX-INF-WARNING message name +static constexpr uint16_t UBX_LOG_CREATE_MSGID = 0x07; //!< UBX-LOG-CREATE message ID +static constexpr const char* UBX_LOG_CREATE_STRID = "UBX-LOG-CREATE"; //!< UBX-LOG-CREATE message name +static constexpr uint16_t UBX_LOG_ERASE_MSGID = 0x03; //!< UBX-LOG-ERASE message ID +static constexpr const char* UBX_LOG_ERASE_STRID = "UBX-LOG-ERASE"; //!< UBX-LOG-ERASE message name +static constexpr uint16_t UBX_LOG_FINDTIME_MSGID = 0x0e; //!< UBX-LOG-FINDTIME message ID +static constexpr const char* UBX_LOG_FINDTIME_STRID = "UBX-LOG-FINDTIME"; //!< UBX-LOG-FINDTIME message name +static constexpr uint16_t UBX_LOG_INFO_MSGID = 0x08; //!< UBX-LOG-INFO message ID +static constexpr const char* UBX_LOG_INFO_STRID = "UBX-LOG-INFO"; //!< UBX-LOG-INFO message name +static constexpr uint16_t UBX_LOG_RETR_MSGID = 0x09; //!< UBX-LOG-RETR message ID +static constexpr const char* UBX_LOG_RETR_STRID = "UBX-LOG-RETR"; //!< UBX-LOG-RETR message name +static constexpr uint16_t UBX_LOG_RETRPOS_MSGID = 0x0b; //!< UBX-LOG-RETRPOS message ID +static constexpr const char* UBX_LOG_RETRPOS_STRID = "UBX-LOG-RETRPOS"; //!< UBX-LOG-RETRPOS message name +static constexpr uint16_t UBX_LOG_RETRPOSX_MSGID = 0x0f; //!< UBX-LOG-RETRPOSX message ID +static constexpr const char* UBX_LOG_RETRPOSX_STRID = "UBX-LOG-RETRPOSX"; //!< UBX-LOG-RETRPOSX message name +static constexpr uint16_t UBX_LOG_RETRSTR_MSGID = 0x0d; //!< UBX-LOG-RETRSTR message ID +static constexpr const char* UBX_LOG_RETRSTR_STRID = "UBX-LOG-RETRSTR"; //!< UBX-LOG-RETRSTR message name +static constexpr uint16_t UBX_LOG_STR_MSGID = 0x04; //!< UBX-LOG-STR message ID +static constexpr const char* UBX_LOG_STR_STRID = "UBX-LOG-STR"; //!< UBX-LOG-STR message name +static constexpr uint16_t UBX_MGA_ACK_MSGID = 0x60; //!< UBX-MGA-ACK message ID +static constexpr const char* UBX_MGA_ACK_STRID = "UBX-MGA-ACK"; //!< UBX-MGA-ACK message name +static constexpr uint16_t UBX_MGA_BDS_MSGID = 0x03; //!< UBX-MGA-BDS message ID +static constexpr const char* UBX_MGA_BDS_STRID = "UBX-MGA-BDS"; //!< UBX-MGA-BDS message name +static constexpr uint16_t UBX_MGA_DBD_MSGID = 0x80; //!< UBX-MGA-DBD message ID +static constexpr const char* UBX_MGA_DBD_STRID = "UBX-MGA-DBD"; //!< UBX-MGA-DBD message name +static constexpr uint16_t UBX_MGA_GAL_MSGID = 0x02; //!< UBX-MGA-GAL message ID +static constexpr const char* UBX_MGA_GAL_STRID = "UBX-MGA-GAL"; //!< UBX-MGA-GAL message name +static constexpr uint16_t UBX_MGA_GLO_MSGID = 0x06; //!< UBX-MGA-GLO message ID +static constexpr const char* UBX_MGA_GLO_STRID = "UBX-MGA-GLO"; //!< UBX-MGA-GLO message name +static constexpr uint16_t UBX_MGA_GPS_MSGID = 0x00; //!< UBX-MGA-GPS message ID +static constexpr const char* UBX_MGA_GPS_STRID = "UBX-MGA-GPS"; //!< UBX-MGA-GPS message name +static constexpr uint16_t UBX_MGA_INI_MSGID = 0x40; //!< UBX-MGA-INI message ID +static constexpr const char* UBX_MGA_INI_STRID = "UBX-MGA-INI"; //!< UBX-MGA-INI message name +static constexpr uint16_t UBX_MGA_QZSS_MSGID = 0x05; //!< UBX-MGA-QZSS message ID +static constexpr const char* UBX_MGA_QZSS_STRID = "UBX-MGA-QZSS"; //!< UBX-MGA-QZSS message name +static constexpr uint16_t UBX_MON_COMMS_MSGID = 0x36; //!< UBX-MON-COMMS message ID +static constexpr const char* UBX_MON_COMMS_STRID = "UBX-MON-COMMS"; //!< UBX-MON-COMMS message name +static constexpr uint16_t UBX_MON_GNSS_MSGID = 0x28; //!< UBX-MON-GNSS message ID +static constexpr const char* UBX_MON_GNSS_STRID = "UBX-MON-GNSS"; //!< UBX-MON-GNSS message name +static constexpr uint16_t UBX_MON_HW_MSGID = 0x09; //!< UBX-MON-HW message ID +static constexpr const char* UBX_MON_HW_STRID = "UBX-MON-HW"; //!< UBX-MON-HW message name +static constexpr uint16_t UBX_MON_HW2_MSGID = 0x0b; //!< UBX-MON-HW2 message ID +static constexpr const char* UBX_MON_HW2_STRID = "UBX-MON-HW2"; //!< UBX-MON-HW2 message name +static constexpr uint16_t UBX_MON_HW3_MSGID = 0x37; //!< UBX-MON-HW3 message ID +static constexpr const char* UBX_MON_HW3_STRID = "UBX-MON-HW3"; //!< UBX-MON-HW3 message name +static constexpr uint16_t UBX_MON_IO_MSGID = 0x02; //!< UBX-MON-IO message ID +static constexpr const char* UBX_MON_IO_STRID = "UBX-MON-IO"; //!< UBX-MON-IO message name +static constexpr uint16_t UBX_MON_MSGPP_MSGID = 0x06; //!< UBX-MON-MSGPP message ID +static constexpr const char* UBX_MON_MSGPP_STRID = "UBX-MON-MSGPP"; //!< UBX-MON-MSGPP message name +static constexpr uint16_t UBX_MON_PATCH_MSGID = 0x27; //!< UBX-MON-PATCH message ID +static constexpr const char* UBX_MON_PATCH_STRID = "UBX-MON-PATCH"; //!< UBX-MON-PATCH message name +static constexpr uint16_t UBX_MON_RF_MSGID = 0x38; //!< UBX-MON-RF message ID +static constexpr const char* UBX_MON_RF_STRID = "UBX-MON-RF"; //!< UBX-MON-RF message name +static constexpr uint16_t UBX_MON_RXBUF_MSGID = 0x07; //!< UBX-MON-RXBUF message ID +static constexpr const char* UBX_MON_RXBUF_STRID = "UBX-MON-RXBUF"; //!< UBX-MON-RXBUF message name +static constexpr uint16_t UBX_MON_RXR_MSGID = 0x21; //!< UBX-MON-RXR message ID +static constexpr const char* UBX_MON_RXR_STRID = "UBX-MON-RXR"; //!< UBX-MON-RXR message name +static constexpr uint16_t UBX_MON_SPAN_MSGID = 0x31; //!< UBX-MON-SPAN message ID +static constexpr const char* UBX_MON_SPAN_STRID = "UBX-MON-SPAN"; //!< UBX-MON-SPAN message name +static constexpr uint16_t UBX_MON_SYS_MSGID = 0x39; //!< UBX-MON-SYS message ID +static constexpr const char* UBX_MON_SYS_STRID = "UBX-MON-SYS"; //!< UBX-MON-SYS message name +static constexpr uint16_t UBX_MON_TEMP_MSGID = 0x0e; //!< UBX-MON-TEMP message ID +static constexpr const char* UBX_MON_TEMP_STRID = "UBX-MON-TEMP"; //!< UBX-MON-TEMP message name +static constexpr uint16_t UBX_MON_TXBUF_MSGID = 0x08; //!< UBX-MON-TXBUF message ID +static constexpr const char* UBX_MON_TXBUF_STRID = "UBX-MON-TXBUF"; //!< UBX-MON-TXBUF message name +static constexpr uint16_t UBX_MON_VER_MSGID = 0x04; //!< UBX-MON-VER message ID +static constexpr const char* UBX_MON_VER_STRID = "UBX-MON-VER"; //!< UBX-MON-VER message name +static constexpr uint16_t UBX_NAV_ATT_MSGID = 0x05; //!< UBX-NAV-ATT message ID +static constexpr const char* UBX_NAV_ATT_STRID = "UBX-NAV-ATT"; //!< UBX-NAV-ATT message name +static constexpr uint16_t UBX_NAV_CLOCK_MSGID = 0x22; //!< UBX-NAV-CLOCK message ID +static constexpr const char* UBX_NAV_CLOCK_STRID = "UBX-NAV-CLOCK"; //!< UBX-NAV-CLOCK message name +static constexpr uint16_t UBX_NAV_COV_MSGID = 0x36; //!< UBX-NAV-COV message ID +static constexpr const char* UBX_NAV_COV_STRID = "UBX-NAV-COV"; //!< UBX-NAV-COV message name +static constexpr uint16_t UBX_NAV_DOP_MSGID = 0x04; //!< UBX-NAV-DOP message ID +static constexpr const char* UBX_NAV_DOP_STRID = "UBX-NAV-DOP"; //!< UBX-NAV-DOP message name +static constexpr uint16_t UBX_NAV_EELL_MSGID = 0x3d; //!< UBX-NAV-EELL message ID +static constexpr const char* UBX_NAV_EELL_STRID = "UBX-NAV-EELL"; //!< UBX-NAV-EELL message name +static constexpr uint16_t UBX_NAV_EOE_MSGID = 0x61; //!< UBX-NAV-EOE message ID +static constexpr const char* UBX_NAV_EOE_STRID = "UBX-NAV-EOE"; //!< UBX-NAV-EOE message name +static constexpr uint16_t UBX_NAV_GEOFENCE_MSGID = 0x39; //!< UBX-NAV-GEOFENCE message ID +static constexpr const char* UBX_NAV_GEOFENCE_STRID = "UBX-NAV-GEOFENCE"; //!< UBX-NAV-GEOFENCE message name +static constexpr uint16_t UBX_NAV_HPPOSECEF_MSGID = 0x13; //!< UBX-NAV-HPPOSECEF message ID +static constexpr const char* UBX_NAV_HPPOSECEF_STRID = "UBX-NAV-HPPOSECEF"; //!< UBX-NAV-HPPOSECEF message name +static constexpr uint16_t UBX_NAV_HPPOSLLH_MSGID = 0x14; //!< UBX-NAV-HPPOSLLH message ID +static constexpr const char* UBX_NAV_HPPOSLLH_STRID = "UBX-NAV-HPPOSLLH"; //!< UBX-NAV-HPPOSLLH message name +static constexpr uint16_t UBX_NAV_ODO_MSGID = 0x09; //!< UBX-NAV-ODO message ID +static constexpr const char* UBX_NAV_ODO_STRID = "UBX-NAV-ODO"; //!< UBX-NAV-ODO message name +static constexpr uint16_t UBX_NAV_ORB_MSGID = 0x34; //!< UBX-NAV-ORB message ID +static constexpr const char* UBX_NAV_ORB_STRID = "UBX-NAV-ORB"; //!< UBX-NAV-ORB message name +static constexpr uint16_t UBX_NAV_PL_MSGID = 0x62; //!< UBX-NAV-PL message ID +static constexpr const char* UBX_NAV_PL_STRID = "UBX-NAV-PL"; //!< UBX-NAV-PL message name +static constexpr uint16_t UBX_NAV_POSECEF_MSGID = 0x01; //!< UBX-NAV-POSECEF message ID +static constexpr const char* UBX_NAV_POSECEF_STRID = "UBX-NAV-POSECEF"; //!< UBX-NAV-POSECEF message name +static constexpr uint16_t UBX_NAV_POSLLH_MSGID = 0x02; //!< UBX-NAV-POSLLH message ID +static constexpr const char* UBX_NAV_POSLLH_STRID = "UBX-NAV-POSLLH"; //!< UBX-NAV-POSLLH message name +static constexpr uint16_t UBX_NAV_PVAT_MSGID = 0x17; //!< UBX-NAV-PVAT message ID +static constexpr const char* UBX_NAV_PVAT_STRID = "UBX-NAV-PVAT"; //!< UBX-NAV-PVAT message name +static constexpr uint16_t UBX_NAV_PVT_MSGID = 0x07; //!< UBX-NAV-PVT message ID +static constexpr const char* UBX_NAV_PVT_STRID = "UBX-NAV-PVT"; //!< UBX-NAV-PVT message name +static constexpr uint16_t UBX_NAV_RELPOSNED_MSGID = 0x3c; //!< UBX-NAV-RELPOSNED message ID +static constexpr const char* UBX_NAV_RELPOSNED_STRID = "UBX-NAV-RELPOSNED"; //!< UBX-NAV-RELPOSNED message name +static constexpr uint16_t UBX_NAV_RESETODO_MSGID = 0x10; //!< UBX-NAV-RESETODO message ID +static constexpr const char* UBX_NAV_RESETODO_STRID = "UBX-NAV-RESETODO"; //!< UBX-NAV-RESETODO message name +static constexpr uint16_t UBX_NAV_SAT_MSGID = 0x35; //!< UBX-NAV-SAT message ID +static constexpr const char* UBX_NAV_SAT_STRID = "UBX-NAV-SAT"; //!< UBX-NAV-SAT message name +static constexpr uint16_t UBX_NAV_SBAS_MSGID = 0x32; //!< UBX-NAV-SBAS message ID +static constexpr const char* UBX_NAV_SBAS_STRID = "UBX-NAV-SBAS"; //!< UBX-NAV-SBAS message name +static constexpr uint16_t UBX_NAV_SIG_MSGID = 0x43; //!< UBX-NAV-SIG message ID +static constexpr const char* UBX_NAV_SIG_STRID = "UBX-NAV-SIG"; //!< UBX-NAV-SIG message name +static constexpr uint16_t UBX_NAV_SLAS_MSGID = 0x42; //!< UBX-NAV-SLAS message ID +static constexpr const char* UBX_NAV_SLAS_STRID = "UBX-NAV-SLAS"; //!< UBX-NAV-SLAS message name +static constexpr uint16_t UBX_NAV_STATUS_MSGID = 0x03; //!< UBX-NAV-STATUS message ID +static constexpr const char* UBX_NAV_STATUS_STRID = "UBX-NAV-STATUS"; //!< UBX-NAV-STATUS message name +static constexpr uint16_t UBX_NAV_SVIN_MSGID = 0x3b; //!< UBX-NAV-SVIN message ID +static constexpr const char* UBX_NAV_SVIN_STRID = "UBX-NAV-SVIN"; //!< UBX-NAV-SVIN message name +static constexpr uint16_t UBX_NAV_TIMEBDS_MSGID = 0x24; //!< UBX-NAV-TIMEBDS message ID +static constexpr const char* UBX_NAV_TIMEBDS_STRID = "UBX-NAV-TIMEBDS"; //!< UBX-NAV-TIMEBDS message name +static constexpr uint16_t UBX_NAV_TIMEGAL_MSGID = 0x25; //!< UBX-NAV-TIMEGAL message ID +static constexpr const char* UBX_NAV_TIMEGAL_STRID = "UBX-NAV-TIMEGAL"; //!< UBX-NAV-TIMEGAL message name +static constexpr uint16_t UBX_NAV_TIMEGLO_MSGID = 0x23; //!< UBX-NAV-TIMEGLO message ID +static constexpr const char* UBX_NAV_TIMEGLO_STRID = "UBX-NAV-TIMEGLO"; //!< UBX-NAV-TIMEGLO message name +static constexpr uint16_t UBX_NAV_TIMEGPS_MSGID = 0x20; //!< UBX-NAV-TIMEGPS message ID +static constexpr const char* UBX_NAV_TIMEGPS_STRID = "UBX-NAV-TIMEGPS"; //!< UBX-NAV-TIMEGPS message name +static constexpr uint16_t UBX_NAV_TIMELS_MSGID = 0x26; //!< UBX-NAV-TIMELS message ID +static constexpr const char* UBX_NAV_TIMELS_STRID = "UBX-NAV-TIMELS"; //!< UBX-NAV-TIMELS message name +static constexpr uint16_t UBX_NAV_TIMEQZSS_MSGID = 0x27; //!< UBX-NAV-TIMEQZSS message ID +static constexpr const char* UBX_NAV_TIMEQZSS_STRID = "UBX-NAV-TIMEQZSS"; //!< UBX-NAV-TIMEQZSS message name +static constexpr uint16_t UBX_NAV_TIMETRUSTED_MSGID = 0x64; //!< UBX-NAV-TIMETRUSTED message ID +static constexpr const char* UBX_NAV_TIMETRUSTED_STRID = "UBX-NAV-TIMETRUSTED"; //!< UBX-NAV-TIMETRUSTED message name +static constexpr uint16_t UBX_NAV_TIMEUTC_MSGID = 0x21; //!< UBX-NAV-TIMEUTC message ID +static constexpr const char* UBX_NAV_TIMEUTC_STRID = "UBX-NAV-TIMEUTC"; //!< UBX-NAV-TIMEUTC message name +static constexpr uint16_t UBX_NAV_VELECEF_MSGID = 0x11; //!< UBX-NAV-VELECEF message ID +static constexpr const char* UBX_NAV_VELECEF_STRID = "UBX-NAV-VELECEF"; //!< UBX-NAV-VELECEF message name +static constexpr uint16_t UBX_NAV_VELNED_MSGID = 0x12; //!< UBX-NAV-VELNED message ID +static constexpr const char* UBX_NAV_VELNED_STRID = "UBX-NAV-VELNED"; //!< UBX-NAV-VELNED message name +static constexpr uint16_t UBX_NAV2_CLOCK_MSGID = UBX_NAV_CLOCK_MSGID; //!< UBX-NAV2-CLOCK message ID +static constexpr const char* UBX_NAV2_CLOCK_STRID = "UBX-NAV2-CLOCK"; //!< UBX-NAV2-CLOCK message name +static constexpr uint16_t UBX_NAV2_COV_MSGID = UBX_NAV_COV_MSGID; //!< UBX-NAV2-COV message ID +static constexpr const char* UBX_NAV2_COV_STRID = "UBX-NAV2-COV"; //!< UBX-NAV2-COV message name +static constexpr uint16_t UBX_NAV2_DOP_MSGID = UBX_NAV_DOP_MSGID; //!< UBX-NAV2-DOP message ID +static constexpr const char* UBX_NAV2_DOP_STRID = "UBX-NAV2-DOP"; //!< UBX-NAV2-DOP message name +static constexpr uint16_t UBX_NAV2_EOE_MSGID = UBX_NAV_EOE_MSGID; //!< UBX-NAV2-EOE message ID +static constexpr const char* UBX_NAV2_EOE_STRID = "UBX-NAV2-EOE"; //!< UBX-NAV2-EOE message name +static constexpr uint16_t UBX_NAV2_ODO_MSGID = UBX_NAV_ODO_MSGID; //!< UBX-NAV2-ODO message ID +static constexpr const char* UBX_NAV2_ODO_STRID = "UBX-NAV2-ODO"; //!< UBX-NAV2-ODO message name +static constexpr uint16_t UBX_NAV2_POSECEF_MSGID = UBX_NAV_POSECEF_MSGID; //!< UBX-NAV2-POSECEF message ID +static constexpr const char* UBX_NAV2_POSECEF_STRID = "UBX-NAV2-POSECEF"; //!< UBX-NAV2-POSECEF message name +static constexpr uint16_t UBX_NAV2_POSLLH_MSGID = UBX_NAV_POSLLH_MSGID; //!< UBX-NAV2-POSLLH message ID +static constexpr const char* UBX_NAV2_POSLLH_STRID = "UBX-NAV2-POSLLH"; //!< UBX-NAV2-POSLLH message name +static constexpr uint16_t UBX_NAV2_PVT_MSGID = UBX_NAV_PVT_MSGID; //!< UBX-NAV2-PVT message ID +static constexpr const char* UBX_NAV2_PVT_STRID = "UBX-NAV2-PVT"; //!< UBX-NAV2-PVT message name +static constexpr uint16_t UBX_NAV2_SAT_MSGID = UBX_NAV_SAT_MSGID; //!< UBX-NAV2-SAT message ID +static constexpr const char* UBX_NAV2_SAT_STRID = "UBX-NAV2-SAT"; //!< UBX-NAV2-SAT message name +static constexpr uint16_t UBX_NAV2_SBAS_MSGID = UBX_NAV_SBAS_MSGID; //!< UBX-NAV2-SBAS message ID +static constexpr const char* UBX_NAV2_SBAS_STRID = "UBX-NAV2-SBAS"; //!< UBX-NAV2-SBAS message name +static constexpr uint16_t UBX_NAV2_SIG_MSGID = UBX_NAV_SIG_MSGID; //!< UBX-NAV2-SIG message ID +static constexpr const char* UBX_NAV2_SIG_STRID = "UBX-NAV2-SIG"; //!< UBX-NAV2-SIG message name +static constexpr uint16_t UBX_NAV2_SLAS_MSGID = UBX_NAV_SLAS_MSGID; //!< UBX-NAV2-SLAS message ID +static constexpr const char* UBX_NAV2_SLAS_STRID = "UBX-NAV2-SLAS"; //!< UBX-NAV2-SLAS message name +static constexpr uint16_t UBX_NAV2_STATUS_MSGID = UBX_NAV_STATUS_MSGID; //!< UBX-NAV2-STATUS message ID +static constexpr const char* UBX_NAV2_STATUS_STRID = "UBX-NAV2-STATUS"; //!< UBX-NAV2-STATUS message name +static constexpr uint16_t UBX_NAV2_SVIN_MSGID = UBX_NAV_SVIN_MSGID; //!< UBX-NAV2-SVIN message ID +static constexpr const char* UBX_NAV2_SVIN_STRID = "UBX-NAV2-SVIN"; //!< UBX-NAV2-SVIN message name +static constexpr uint16_t UBX_NAV2_TIMEBDS_MSGID = UBX_NAV_TIMEBDS_MSGID; //!< UBX-NAV2-TIMEBDS message ID +static constexpr const char* UBX_NAV2_TIMEBDS_STRID = "UBX-NAV2-TIMEBDS"; //!< UBX-NAV2-TIMEBDS message name +static constexpr uint16_t UBX_NAV2_TIMEGAL_MSGID = UBX_NAV_TIMEGAL_MSGID; //!< UBX-NAV2-TIMEGAL message ID +static constexpr const char* UBX_NAV2_TIMEGAL_STRID = "UBX-NAV2-TIMEGAL"; //!< UBX-NAV2-TIMEGAL message name +static constexpr uint16_t UBX_NAV2_TIMEGLO_MSGID = UBX_NAV_TIMEGLO_MSGID; //!< UBX-NAV2-TIMEGLO message ID +static constexpr const char* UBX_NAV2_TIMEGLO_STRID = "UBX-NAV2-TIMEGLO"; //!< UBX-NAV2-TIMEGLO message name +static constexpr uint16_t UBX_NAV2_TIMEGPS_MSGID = UBX_NAV_TIMEGPS_MSGID; //!< UBX-NAV2-TIMEGPS message ID +static constexpr const char* UBX_NAV2_TIMEGPS_STRID = "UBX-NAV2-TIMEGPS"; //!< UBX-NAV2-TIMEGPS message name +static constexpr uint16_t UBX_NAV2_TIMELS_MSGID = UBX_NAV_TIMELS_MSGID; //!< UBX-NAV2-TIMELS message ID +static constexpr const char* UBX_NAV2_TIMELS_STRID = "UBX-NAV2-TIMELS"; //!< UBX-NAV2-TIMELS message name +static constexpr uint16_t UBX_NAV2_TIMEQZSS_MSGID = UBX_NAV_TIMEQZSS_MSGID; //!< UBX-NAV2-TIMEQZSS message ID +static constexpr const char* UBX_NAV2_TIMEQZSS_STRID = "UBX-NAV2-TIMEQZSS"; //!< UBX-NAV2-TIMEQZSS message name +static constexpr uint16_t UBX_NAV2_TIMEUTC_MSGID = UBX_NAV_TIMEUTC_MSGID; //!< UBX-NAV2-TIMEUTC message ID +static constexpr const char* UBX_NAV2_TIMEUTC_STRID = "UBX-NAV2-TIMEUTC"; //!< UBX-NAV2-TIMEUTC message name +static constexpr uint16_t UBX_NAV2_VELECEF_MSGID = UBX_NAV_VELECEF_MSGID; //!< UBX-NAV2-VELECEF message ID +static constexpr const char* UBX_NAV2_VELECEF_STRID = "UBX-NAV2-VELECEF"; //!< UBX-NAV2-VELECEF message name +static constexpr uint16_t UBX_NAV2_VELNED_MSGID = UBX_NAV_VELNED_MSGID; //!< UBX-NAV2-VELNED message ID +static constexpr const char* UBX_NAV2_VELNED_STRID = "UBX-NAV2-VELNED"; //!< UBX-NAV2-VELNED message name +static constexpr uint16_t UBX_RXM_COR_MSGID = 0x14; //!< UBX-RXM-COR message ID +static constexpr const char* UBX_RXM_COR_STRID = "UBX-RXM-COR"; //!< UBX-RXM-COR message name +static constexpr uint16_t UBX_RXM_MEASX_MSGID = 0x14; //!< UBX-RXM-MEASX message ID +static constexpr const char* UBX_RXM_MEASX_STRID = "UBX-RXM-MEASX"; //!< UBX-RXM-MEASX message name +static constexpr uint16_t UBX_RXM_PMP_MSGID = 0x72; //!< UBX-RXM-PMP message ID +static constexpr const char* UBX_RXM_PMP_STRID = "UBX-RXM-PMP"; //!< UBX-RXM-PMP message name +static constexpr uint16_t UBX_RXM_PMREQ_MSGID = 0x41; //!< UBX-RXM-PMREQ message ID +static constexpr const char* UBX_RXM_PMREQ_STRID = "UBX-RXM-PMREQ"; //!< UBX-RXM-PMREQ message name +static constexpr uint16_t UBX_RXM_QZSSL6_MSGID = 0x73; //!< UBX-RXM-QZSSL6 message ID +static constexpr const char* UBX_RXM_QZSSL6_STRID = "UBX-RXM-QZSSL6"; //!< UBX-RXM-QZSSL6 message name +static constexpr uint16_t UBX_RXM_RAWX_MSGID = 0x15; //!< UBX-RXM-RAWX message ID +static constexpr const char* UBX_RXM_RAWX_STRID = "UBX-RXM-RAWX"; //!< UBX-RXM-RAWX message name +static constexpr uint16_t UBX_RXM_RLM_MSGID = 0x59; //!< UBX-RXM-RLM message ID +static constexpr const char* UBX_RXM_RLM_STRID = "UBX-RXM-RLM"; //!< UBX-RXM-RLM message name +static constexpr uint16_t UBX_RXM_RTCM_MSGID = 0x32; //!< UBX-RXM-RTCM message ID +static constexpr const char* UBX_RXM_RTCM_STRID = "UBX-RXM-RTCM"; //!< UBX-RXM-RTCM message name +static constexpr uint16_t UBX_RXM_SFRBX_MSGID = 0x13; //!< UBX-RXM-SFRBX message ID +static constexpr const char* UBX_RXM_SFRBX_STRID = "UBX-RXM-SFRBX"; //!< UBX-RXM-SFRBX message name +static constexpr uint16_t UBX_RXM_SPARTN_MSGID = 0x33; //!< UBX-RXM-SPARTN message ID +static constexpr const char* UBX_RXM_SPARTN_STRID = "UBX-RXM-SPARTN"; //!< UBX-RXM-SPARTN message name +static constexpr uint16_t UBX_RXM_SPARTNKEY_MSGID = 0x36; //!< UBX-RXM-SPARTNKEY message ID +static constexpr const char* UBX_RXM_SPARTNKEY_STRID = "UBX-RXM-SPARTNKEY"; //!< UBX-RXM-SPARTNKEY message name +static constexpr uint16_t UBX_SEC_OSNMA_MSGID = 0x0a; //!< UBX-SEC-OSNMA message ID +static constexpr const char* UBX_SEC_OSNMA_STRID = "UBX-SEC-OSNMA"; //!< UBX-SEC-OSNMA message name +static constexpr uint16_t UBX_SEC_SIG_MSGID = 0x09; //!< UBX-SEC-SIG message ID +static constexpr const char* UBX_SEC_SIG_STRID = "UBX-SEC-SIG"; //!< UBX-SEC-SIG message name +static constexpr uint16_t UBX_SEC_SIGLOG_MSGID = 0x10; //!< UBX-SEC-SIGLOG message ID +static constexpr const char* UBX_SEC_SIGLOG_STRID = "UBX-SEC-SIGLOG"; //!< UBX-SEC-SIGLOG message name +static constexpr uint16_t UBX_SEC_UNIQID_MSGID = 0x03; //!< UBX-SEC-UNIQID message ID +static constexpr const char* UBX_SEC_UNIQID_STRID = "UBX-SEC-UNIQID"; //!< UBX-SEC-UNIQID message name +static constexpr uint16_t UBX_TIM_TM2_MSGID = 0x03; //!< UBX-TIM-TM2 message ID +static constexpr const char* UBX_TIM_TM2_STRID = "UBX-TIM-TM2"; //!< UBX-TIM-TM2 message name +static constexpr uint16_t UBX_TIM_TP_MSGID = 0x01; //!< UBX-TIM-TP message ID +static constexpr const char* UBX_TIM_TP_STRID = "UBX-TIM-TP"; //!< UBX-TIM-TP message name +static constexpr uint16_t UBX_TIM_VRFY_MSGID = 0x06; //!< UBX-TIM-VRFY message ID +static constexpr const char* UBX_TIM_VRFY_STRID = "UBX-TIM-VRFY"; //!< UBX-TIM-VRFY message name +static constexpr uint16_t UBX_UPD_FLDET_MSGID = 0x08; //!< UBX-UPD-FLDET message ID +static constexpr const char* UBX_UPD_FLDET_STRID = "UBX-UPD-FLDET"; //!< UBX-UPD-FLDET message name +static constexpr uint16_t UBX_UPD_POS_MSGID = 0x15; //!< UBX-UPD-POS message ID +static constexpr const char* UBX_UPD_POS_STRID = "UBX-UPD-POS"; //!< UBX-UPD-POS message name +static constexpr uint16_t UBX_UPD_SAFEBOOT_MSGID = 0x07; //!< UBX-UPD-SAFEBOOT message ID +static constexpr const char* UBX_UPD_SAFEBOOT_STRID = "UBX-UPD-SAFEBOOT"; //!< UBX-UPD-SAFEBOOT message name +static constexpr uint16_t UBX_UPD_SOS_MSGID = 0x14; //!< UBX-UPD-SOS message ID +static constexpr const char* UBX_UPD_SOS_STRID = "UBX-UPD-SOS"; //!< UBX-UPD-SOS message name +static constexpr uint16_t UBX_NMEA_STANDARD_DTM_MSGID = 0x0a; //!< UBX-NMEA-STANDARD_DTM message ID +static constexpr const char* UBX_NMEA_STANDARD_DTM_STRID = "UBX-NMEA-STANDARD_DTM"; //!< UBX-NMEA-STANDARD_DTM message name +static constexpr uint16_t UBX_NMEA_STANDARD_GAQ_MSGID = 0x45; //!< UBX-NMEA-STANDARD_GAQ message ID +static constexpr const char* UBX_NMEA_STANDARD_GAQ_STRID = "UBX-NMEA-STANDARD_GAQ"; //!< UBX-NMEA-STANDARD_GAQ message name +static constexpr uint16_t UBX_NMEA_STANDARD_GBQ_MSGID = 0x44; //!< UBX-NMEA-STANDARD_GBQ message ID +static constexpr const char* UBX_NMEA_STANDARD_GBQ_STRID = "UBX-NMEA-STANDARD_GBQ"; //!< UBX-NMEA-STANDARD_GBQ message name +static constexpr uint16_t UBX_NMEA_STANDARD_GBS_MSGID = 0x09; //!< UBX-NMEA-STANDARD_GBS message ID +static constexpr const char* UBX_NMEA_STANDARD_GBS_STRID = "UBX-NMEA-STANDARD_GBS"; //!< UBX-NMEA-STANDARD_GBS message name +static constexpr uint16_t UBX_NMEA_STANDARD_GGA_MSGID = 0x00; //!< UBX-NMEA-STANDARD_GGA message ID +static constexpr const char* UBX_NMEA_STANDARD_GGA_STRID = "UBX-NMEA-STANDARD_GGA"; //!< UBX-NMEA-STANDARD_GGA message name +static constexpr uint16_t UBX_NMEA_STANDARD_GLL_MSGID = 0x01; //!< UBX-NMEA-STANDARD_GLL message ID +static constexpr const char* UBX_NMEA_STANDARD_GLL_STRID = "UBX-NMEA-STANDARD_GLL"; //!< UBX-NMEA-STANDARD_GLL message name +static constexpr uint16_t UBX_NMEA_STANDARD_GLQ_MSGID = 0x43; //!< UBX-NMEA-STANDARD_GLQ message ID +static constexpr const char* UBX_NMEA_STANDARD_GLQ_STRID = "UBX-NMEA-STANDARD_GLQ"; //!< UBX-NMEA-STANDARD_GLQ message name +static constexpr uint16_t UBX_NMEA_STANDARD_GNQ_MSGID = 0x42; //!< UBX-NMEA-STANDARD_GNQ message ID +static constexpr const char* UBX_NMEA_STANDARD_GNQ_STRID = "UBX-NMEA-STANDARD_GNQ"; //!< UBX-NMEA-STANDARD_GNQ message name +static constexpr uint16_t UBX_NMEA_STANDARD_GNS_MSGID = 0x0d; //!< UBX-NMEA-STANDARD_GNS message ID +static constexpr const char* UBX_NMEA_STANDARD_GNS_STRID = "UBX-NMEA-STANDARD_GNS"; //!< UBX-NMEA-STANDARD_GNS message name +static constexpr uint16_t UBX_NMEA_STANDARD_GPQ_MSGID = 0x40; //!< UBX-NMEA-STANDARD_GPQ message ID +static constexpr const char* UBX_NMEA_STANDARD_GPQ_STRID = "UBX-NMEA-STANDARD_GPQ"; //!< UBX-NMEA-STANDARD_GPQ message name +static constexpr uint16_t UBX_NMEA_STANDARD_GQQ_MSGID = 0x47; //!< UBX-NMEA-STANDARD_GQQ message ID +static constexpr const char* UBX_NMEA_STANDARD_GQQ_STRID = "UBX-NMEA-STANDARD_GQQ"; //!< UBX-NMEA-STANDARD_GQQ message name +static constexpr uint16_t UBX_NMEA_STANDARD_GRS_MSGID = 0x06; //!< UBX-NMEA-STANDARD_GRS message ID +static constexpr const char* UBX_NMEA_STANDARD_GRS_STRID = "UBX-NMEA-STANDARD_GRS"; //!< UBX-NMEA-STANDARD_GRS message name +static constexpr uint16_t UBX_NMEA_STANDARD_GSA_MSGID = 0x02; //!< UBX-NMEA-STANDARD_GSA message ID +static constexpr const char* UBX_NMEA_STANDARD_GSA_STRID = "UBX-NMEA-STANDARD_GSA"; //!< UBX-NMEA-STANDARD_GSA message name +static constexpr uint16_t UBX_NMEA_STANDARD_GST_MSGID = 0x07; //!< UBX-NMEA-STANDARD_GST message ID +static constexpr const char* UBX_NMEA_STANDARD_GST_STRID = "UBX-NMEA-STANDARD_GST"; //!< UBX-NMEA-STANDARD_GST message name +static constexpr uint16_t UBX_NMEA_STANDARD_GSV_MSGID = 0x03; //!< UBX-NMEA-STANDARD_GSV message ID +static constexpr const char* UBX_NMEA_STANDARD_GSV_STRID = "UBX-NMEA-STANDARD_GSV"; //!< UBX-NMEA-STANDARD_GSV message name +static constexpr uint16_t UBX_NMEA_STANDARD_RLM_MSGID = 0x0b; //!< UBX-NMEA-STANDARD_RLM message ID +static constexpr const char* UBX_NMEA_STANDARD_RLM_STRID = "UBX-NMEA-STANDARD_RLM"; //!< UBX-NMEA-STANDARD_RLM message name +static constexpr uint16_t UBX_NMEA_STANDARD_RMC_MSGID = 0x04; //!< UBX-NMEA-STANDARD_RMC message ID +static constexpr const char* UBX_NMEA_STANDARD_RMC_STRID = "UBX-NMEA-STANDARD_RMC"; //!< UBX-NMEA-STANDARD_RMC message name +static constexpr uint16_t UBX_NMEA_STANDARD_TXT_MSGID = 0x41; //!< UBX-NMEA-STANDARD_TXT message ID +static constexpr const char* UBX_NMEA_STANDARD_TXT_STRID = "UBX-NMEA-STANDARD_TXT"; //!< UBX-NMEA-STANDARD_TXT message name +static constexpr uint16_t UBX_NMEA_STANDARD_VLW_MSGID = 0x0f; //!< UBX-NMEA-STANDARD_VLW message ID +static constexpr const char* UBX_NMEA_STANDARD_VLW_STRID = "UBX-NMEA-STANDARD_VLW"; //!< UBX-NMEA-STANDARD_VLW message name +static constexpr uint16_t UBX_NMEA_STANDARD_VTG_MSGID = 0x05; //!< UBX-NMEA-STANDARD_VTG message ID +static constexpr const char* UBX_NMEA_STANDARD_VTG_STRID = "UBX-NMEA-STANDARD_VTG"; //!< UBX-NMEA-STANDARD_VTG message name +static constexpr uint16_t UBX_NMEA_STANDARD_ZDA_MSGID = 0x08; //!< UBX-NMEA-STANDARD_ZDA message ID +static constexpr const char* UBX_NMEA_STANDARD_ZDA_STRID = "UBX-NMEA-STANDARD_ZDA"; //!< UBX-NMEA-STANDARD_ZDA message name +static constexpr uint16_t UBX_NMEA_PUBX_CONFIG_MSGID = 0x41; //!< UBX-NMEA-PUBX_CONFIG message ID +static constexpr const char* UBX_NMEA_PUBX_CONFIG_STRID = "UBX-NMEA-PUBX_CONFIG"; //!< UBX-NMEA-PUBX_CONFIG message name +static constexpr uint16_t UBX_NMEA_PUBX_POSITION_MSGID = 0x00; //!< UBX-NMEA-PUBX_POSITION message ID +static constexpr const char* UBX_NMEA_PUBX_POSITION_STRID = "UBX-NMEA-PUBX_POSITION"; //!< UBX-NMEA-PUBX_POSITION message name +static constexpr uint16_t UBX_NMEA_PUBX_RATE_MSGID = 0x40; //!< UBX-NMEA-PUBX_RATE message ID +static constexpr const char* UBX_NMEA_PUBX_RATE_STRID = "UBX-NMEA-PUBX_RATE"; //!< UBX-NMEA-PUBX_RATE message name +static constexpr uint16_t UBX_NMEA_PUBX_SVSTATUS_MSGID = 0x03; //!< UBX-NMEA-PUBX_SVSTATUS message ID +static constexpr const char* UBX_NMEA_PUBX_SVSTATUS_STRID = "UBX-NMEA-PUBX_SVSTATUS"; //!< UBX-NMEA-PUBX_SVSTATUS message name +static constexpr uint16_t UBX_NMEA_PUBX_TIME_MSGID = 0x04; //!< UBX-NMEA-PUBX_TIME message ID +static constexpr const char* UBX_NMEA_PUBX_TIME_STRID = "UBX-NMEA-PUBX_TIME"; //!< UBX-NMEA-PUBX_TIME message name +static constexpr uint16_t UBX_RTCM3_TYPE1001_MSGID = 0x01; //!< UBX-RTCM3-TYPE1001 message ID +static constexpr const char* UBX_RTCM3_TYPE1001_STRID = "UBX-RTCM3-TYPE1001"; //!< UBX-RTCM3-TYPE1001 message name +static constexpr uint16_t UBX_RTCM3_TYPE1002_MSGID = 0x02; //!< UBX-RTCM3-TYPE1002 message ID +static constexpr const char* UBX_RTCM3_TYPE1002_STRID = "UBX-RTCM3-TYPE1002"; //!< UBX-RTCM3-TYPE1002 message name +static constexpr uint16_t UBX_RTCM3_TYPE1003_MSGID = 0x03; //!< UBX-RTCM3-TYPE1003 message ID +static constexpr const char* UBX_RTCM3_TYPE1003_STRID = "UBX-RTCM3-TYPE1003"; //!< UBX-RTCM3-TYPE1003 message name +static constexpr uint16_t UBX_RTCM3_TYPE1004_MSGID = 0x04; //!< UBX-RTCM3-TYPE1004 message ID +static constexpr const char* UBX_RTCM3_TYPE1004_STRID = "UBX-RTCM3-TYPE1004"; //!< UBX-RTCM3-TYPE1004 message name +static constexpr uint16_t UBX_RTCM3_TYPE1005_MSGID = 0x05; //!< UBX-RTCM3-TYPE1005 message ID +static constexpr const char* UBX_RTCM3_TYPE1005_STRID = "UBX-RTCM3-TYPE1005"; //!< UBX-RTCM3-TYPE1005 message name +static constexpr uint16_t UBX_RTCM3_TYPE1006_MSGID = 0x06; //!< UBX-RTCM3-TYPE1006 message ID +static constexpr const char* UBX_RTCM3_TYPE1006_STRID = "UBX-RTCM3-TYPE1006"; //!< UBX-RTCM3-TYPE1006 message name +static constexpr uint16_t UBX_RTCM3_TYPE1007_MSGID = 0x07; //!< UBX-RTCM3-TYPE1007 message ID +static constexpr const char* UBX_RTCM3_TYPE1007_STRID = "UBX-RTCM3-TYPE1007"; //!< UBX-RTCM3-TYPE1007 message name +static constexpr uint16_t UBX_RTCM3_TYPE1009_MSGID = 0x09; //!< UBX-RTCM3-TYPE1009 message ID +static constexpr const char* UBX_RTCM3_TYPE1009_STRID = "UBX-RTCM3-TYPE1009"; //!< UBX-RTCM3-TYPE1009 message name +static constexpr uint16_t UBX_RTCM3_TYPE1010_MSGID = 0x0a; //!< UBX-RTCM3-TYPE1010 message ID +static constexpr const char* UBX_RTCM3_TYPE1010_STRID = "UBX-RTCM3-TYPE1010"; //!< UBX-RTCM3-TYPE1010 message name +static constexpr uint16_t UBX_RTCM3_TYPE1011_MSGID = 0xa1; //!< UBX-RTCM3-TYPE1011 message ID +static constexpr const char* UBX_RTCM3_TYPE1011_STRID = "UBX-RTCM3-TYPE1011"; //!< UBX-RTCM3-TYPE1011 message name +static constexpr uint16_t UBX_RTCM3_TYPE1012_MSGID = 0xa2; //!< UBX-RTCM3-TYPE1012 message ID +static constexpr const char* UBX_RTCM3_TYPE1012_STRID = "UBX-RTCM3-TYPE1012"; //!< UBX-RTCM3-TYPE1012 message name +static constexpr uint16_t UBX_RTCM3_TYPE1033_MSGID = 0x21; //!< UBX-RTCM3-TYPE1033 message ID +static constexpr const char* UBX_RTCM3_TYPE1033_STRID = "UBX-RTCM3-TYPE1033"; //!< UBX-RTCM3-TYPE1033 message name +static constexpr uint16_t UBX_RTCM3_TYPE1074_MSGID = 0x4a; //!< UBX-RTCM3-TYPE1074 message ID +static constexpr const char* UBX_RTCM3_TYPE1074_STRID = "UBX-RTCM3-TYPE1074"; //!< UBX-RTCM3-TYPE1074 message name +static constexpr uint16_t UBX_RTCM3_TYPE1075_MSGID = 0x4b; //!< UBX-RTCM3-TYPE1075 message ID +static constexpr const char* UBX_RTCM3_TYPE1075_STRID = "UBX-RTCM3-TYPE1075"; //!< UBX-RTCM3-TYPE1075 message name +static constexpr uint16_t UBX_RTCM3_TYPE1077_MSGID = 0x4d; //!< UBX-RTCM3-TYPE1077 message ID +static constexpr const char* UBX_RTCM3_TYPE1077_STRID = "UBX-RTCM3-TYPE1077"; //!< UBX-RTCM3-TYPE1077 message name +static constexpr uint16_t UBX_RTCM3_TYPE1084_MSGID = 0x54; //!< UBX-RTCM3-TYPE1084 message ID +static constexpr const char* UBX_RTCM3_TYPE1084_STRID = "UBX-RTCM3-TYPE1084"; //!< UBX-RTCM3-TYPE1084 message name +static constexpr uint16_t UBX_RTCM3_TYPE1085_MSGID = 0x55; //!< UBX-RTCM3-TYPE1085 message ID +static constexpr const char* UBX_RTCM3_TYPE1085_STRID = "UBX-RTCM3-TYPE1085"; //!< UBX-RTCM3-TYPE1085 message name +static constexpr uint16_t UBX_RTCM3_TYPE1087_MSGID = 0x57; //!< UBX-RTCM3-TYPE1087 message ID +static constexpr const char* UBX_RTCM3_TYPE1087_STRID = "UBX-RTCM3-TYPE1087"; //!< UBX-RTCM3-TYPE1087 message name +static constexpr uint16_t UBX_RTCM3_TYPE1094_MSGID = 0x5e; //!< UBX-RTCM3-TYPE1094 message ID +static constexpr const char* UBX_RTCM3_TYPE1094_STRID = "UBX-RTCM3-TYPE1094"; //!< UBX-RTCM3-TYPE1094 message name +static constexpr uint16_t UBX_RTCM3_TYPE1095_MSGID = 0x5f; //!< UBX-RTCM3-TYPE1095 message ID +static constexpr const char* UBX_RTCM3_TYPE1095_STRID = "UBX-RTCM3-TYPE1095"; //!< UBX-RTCM3-TYPE1095 message name +static constexpr uint16_t UBX_RTCM3_TYPE1097_MSGID = 0x61; //!< UBX-RTCM3-TYPE1097 message ID +static constexpr const char* UBX_RTCM3_TYPE1097_STRID = "UBX-RTCM3-TYPE1097"; //!< UBX-RTCM3-TYPE1097 message name +static constexpr uint16_t UBX_RTCM3_TYPE1124_MSGID = 0x7c; //!< UBX-RTCM3-TYPE1124 message ID +static constexpr const char* UBX_RTCM3_TYPE1124_STRID = "UBX-RTCM3-TYPE1124"; //!< UBX-RTCM3-TYPE1124 message name +static constexpr uint16_t UBX_RTCM3_TYPE1125_MSGID = 0x7d; //!< UBX-RTCM3-TYPE1125 message ID +static constexpr const char* UBX_RTCM3_TYPE1125_STRID = "UBX-RTCM3-TYPE1125"; //!< UBX-RTCM3-TYPE1125 message name +static constexpr uint16_t UBX_RTCM3_TYPE1127_MSGID = 0x7f; //!< UBX-RTCM3-TYPE1127 message ID +static constexpr const char* UBX_RTCM3_TYPE1127_STRID = "UBX-RTCM3-TYPE1127"; //!< UBX-RTCM3-TYPE1127 message name +static constexpr uint16_t UBX_RTCM3_TYPE1230_MSGID = 0xe6; //!< UBX-RTCM3-TYPE1230 message ID +static constexpr const char* UBX_RTCM3_TYPE1230_STRID = "UBX-RTCM3-TYPE1230"; //!< UBX-RTCM3-TYPE1230 message name +static constexpr uint16_t UBX_RTCM3_TYPE4072_0_MSGID = 0xfe; //!< UBX-RTCM3-TYPE4072_0 message ID +static constexpr const char* UBX_RTCM3_TYPE4072_0_STRID = "UBX-RTCM3-TYPE4072_0"; //!< UBX-RTCM3-TYPE4072_0 message name +static constexpr uint16_t UBX_RTCM3_TYPE4072_1_MSGID = 0xfd; //!< UBX-RTCM3-TYPE4072_1 message ID +static constexpr const char* UBX_RTCM3_TYPE4072_1_STRID = "UBX-RTCM3-TYPE4072_1"; //!< UBX-RTCM3-TYPE4072_1 message name +// @fp_codegen_end{FPSDK_COMMON_PARSER_UBX_MESSAGES} +// clang-format on + +/** + * @brief UBX class/message lookup table entry + */ +struct UbxMsgInfo +{ + uint8_t cls_id_; //!< UBX class ID + uint8_t msg_id_; //!< UBX message ID + const char* name_; //!< UBX name +}; + +// @fp_codegen_begin{FPSDK_COMMON_PARSER_UBX_MSGINFO_HPP} +using UbxClassesInfo = std::array; //!< UBX classes lookup table +using UbxMessagesInfo = std::array; //!< UBX messages lookup table +// @fp_codegen_end{FPSDK_COMMON_PARSER_UBX_MSGINFO_HPP} + +/** + * @brief Get UBX classes lookup table + * + * @returns the UBX classes lookup table + */ +const UbxClassesInfo& UbxGetClassesInfo(); + +/** + * @brief Get UBX messages lookup table + * + * @returns the UBX messages lookup table + */ +const UbxMessagesInfo& UbxGetMessagesInfo(); + +// clang-format on +///@} + +// --------------------------------------------------------------------------------------------------------------------- + +/** + * @name UBX GNSS IDs (gnssId) + * @{ + */ +// clang-format off +static constexpr uint8_t UBX_GNSSID_NONE = 0xff; //!< None +static constexpr uint8_t UBX_GNSSID_GPS = 0; //!< GPS +static constexpr uint8_t UBX_GNSSID_SBAS = 1; //!< SBAS +static constexpr uint8_t UBX_GNSSID_GAL = 2; //!< Galileo +static constexpr uint8_t UBX_GNSSID_BDS = 3; //!< BeiDou +static constexpr uint8_t UBX_GNSSID_QZSS = 5; //!< QZSS +static constexpr uint8_t UBX_GNSSID_GLO = 6; //!< GLONASS +static constexpr uint8_t UBX_GNSSID_NAVIC = 7; //!< NavIC +// clang-format on +///@} + +/** + * @name UBX SV numbering + * @{ + */ +// clang-format off +static constexpr uint8_t UBX_NUM_GPS = 32; //!< G01-G32 +static constexpr uint8_t UBX_NUM_SBAS = 39; //!< S120-S158 +static constexpr uint8_t UBX_NUM_GAL = 36; //!< E01-E36 +static constexpr uint8_t UBX_NUM_BDS = 63; //!< B01-B63 ("Cxx" in RINEX) +static constexpr uint8_t UBX_NUM_QZSS = 10; //!< Q01-Q10 ("Jxx" in RINEX) +static constexpr uint8_t UBX_NUM_GLO = 32; //!< R01-R32 +static constexpr uint8_t UBX_NUM_NAVIC = 14; //!< N01-N14 ("Ixx" in RINEX) +static constexpr uint8_t UBX_FIRST_GPS = 1; //!< G01 +static constexpr uint8_t UBX_FIRST_SBAS = 120; //!< S120 ("Sxx" in RINEX) +static constexpr uint8_t UBX_FIRST_GAL = 1; //!< E01 +static constexpr uint8_t UBX_FIRST_BDS = 1; //!< B01 +static constexpr uint8_t UBX_FIRST_QZSS = 1; //!< Q01 +static constexpr uint8_t UBX_FIRST_GLO = 1; //!< R01 +static constexpr uint8_t UBX_FIRST_NAVIC = 1; //!< N01 +// clang-format on +///@} + +/** + * @name UBX signal IDs (sigId) + * @{ + */ +// clang-format off +static constexpr uint8_t UBX_SIGID_NONE = 0xff; //!< None +static constexpr uint8_t UBX_SIGID_GPS_L1CA = 0; //!< GPS L1 C/A +static constexpr uint8_t UBX_SIGID_GPS_L2CL = 3; //!< GPS L2 CL +static constexpr uint8_t UBX_SIGID_GPS_L2CM = 4; //!< GPS L2 CM +static constexpr uint8_t UBX_SIGID_GPS_L5I = 6; //!< GPS L5 I +static constexpr uint8_t UBX_SIGID_GPS_L5Q = 7; //!< GPS L5 Q +static constexpr uint8_t UBX_SIGID_SBAS_L1CA = 0; //!< SBAS L1 C/A +static constexpr uint8_t UBX_SIGID_GAL_E1C = 0; //!< Galileo E1 C +static constexpr uint8_t UBX_SIGID_GAL_E1B = 1; //!< Galileo E1 B +static constexpr uint8_t UBX_SIGID_GAL_E5AI = 3; //!< Galileo E5 aI +static constexpr uint8_t UBX_SIGID_GAL_E5AQ = 4; //!< Galileo E5 aQ +static constexpr uint8_t UBX_SIGID_GAL_E5BI = 5; //!< Galileo E5 bI +static constexpr uint8_t UBX_SIGID_GAL_E5BQ = 6; //!< Galileo E5 bQ +static constexpr uint8_t UBX_SIGID_BDS_B1ID1 = 0; //!< BeiDou B1I D1 +static constexpr uint8_t UBX_SIGID_BDS_B1ID2 = 1; //!< BeiDou B1I D2 +static constexpr uint8_t UBX_SIGID_BDS_B2ID1 = 2; //!< BeiDou B2I D1 +static constexpr uint8_t UBX_SIGID_BDS_B2ID2 = 3; //!< BeiDou B2I D2 +static constexpr uint8_t UBX_SIGID_BDS_B1CP = 5; //!< BeiDou B1 Cp (pilot) +static constexpr uint8_t UBX_SIGID_BDS_B1CD = 6; //!< BeiDou B1 Cd (data) +static constexpr uint8_t UBX_SIGID_BDS_B2AP = 7; //!< BeiDou B2 ap (pilot) +static constexpr uint8_t UBX_SIGID_BDS_B2AD = 8; //!< BeiDou B2 ad (data) +static constexpr uint8_t UBX_SIGID_QZSS_L1CA = 0; //!< QZSS L1 C/A +static constexpr uint8_t UBX_SIGID_QZSS_L1S = 1; //!< QZSS L1 S +static constexpr uint8_t UBX_SIGID_QZSS_L2CM = 4; //!< QZSS L2 CM +static constexpr uint8_t UBX_SIGID_QZSS_L2CL = 5; //!< QZSS L2 CL +static constexpr uint8_t UBX_SIGID_QZSS_L5I = 8; //!< QZSS L5 I +static constexpr uint8_t UBX_SIGID_QZSS_L5Q = 9; //!< QZSS L5 Q +static constexpr uint8_t UBX_SIGID_GLO_L1OF = 0; //!< GLONASS L1 OF +static constexpr uint8_t UBX_SIGID_GLO_L2OF = 2; //!< GLONASS L2 OF +static constexpr uint8_t UBX_SIGID_NAVIC_L5A = 0; //!< NavIC L5 A +// clang-format on +///@} + +// --------------------------------------------------------------------------------------------------------------------- +/** + * @name UBX-ACK-ACK message + * @{ + */ + +//! UBX-ACK-ACK (version 0, output) payload +struct UBX_ACK_ACK_V0_GROUP0 // clang-format off +{ + uint8_t clsId; //!< Class ID of ack'ed message + uint8_t msgId; //!< Message ID of ack'ed message +}; // clang-format on + +// clang-format off +static constexpr std::size_t UBX_ACK_ACK_V0_SIZE = sizeof(UBX_ACK_ACK_V0_GROUP0) + UBX_FRAME_SIZE; //!< @todo documentation +// clang-format on + +///@} +// --------------------------------------------------------------------------------------------------------------------- +/** + * @name UBX-ACK-NAK message + * @{ + */ + +//! UBX-ACK-NCK (version 0, output) payload +struct UBX_ACK_NAK_V0_GROUP0 // clang-format off +{ + uint8_t clsId; //!< Class ID of not-ack'ed message + uint8_t msgId; //!< Message ID of not-ack'ed message +}; +// clang-format on + +// clang-format off +static constexpr std::size_t UBX_ACK_NAK_V0_SIZE = sizeof(UBX_ACK_NAK_V0_GROUP0) + UBX_FRAME_SIZE; //!< @todo documentation +// clang-format on + +///@} +// --------------------------------------------------------------------------------------------------------------------- +/** + * @name UBX-CFG-VALSET message + * @{ + */ + +//! UBX-CFG-VALSET (version 0, input) message payload header +struct UBX_CFG_VALSET_V0_GROUP0 // clang-format off +{ + uint8_t version; //!< Message version (#UBX_CFG_VALSET_V1_VERSION) + uint8_t layers; //!< Configuration layers + uint8_t reserved[2]; //!< Reserved (set to 0x00) +}; + +static_assert(sizeof(UBX_CFG_VALSET_V0_GROUP0) == 4, ""); + +//! UBX-CFG-VALSET (version 1, input) message payload header +struct UBX_CFG_VALSET_V1_GROUP0 // clang-format off +{ + uint8_t version; //!< Message version (#UBX_CFG_VALSET_V1_VERSION) + uint8_t layers; //!< Configuration layers + uint8_t transaction; //!< Transaction mode + uint8_t reserved; //!< Reserved (set to 0x00) +}; + +static_assert(sizeof(UBX_CFG_VALSET_V1_GROUP0) == 4, ""); + +// clang-format off +static constexpr uint8_t UBX_CFG_VALSET_VERSION_GET(const uint8_t* msg) { return msg[UBX_HEAD_SIZE]; } //!< @todo documentation + +static constexpr uint8_t UBX_CFG_VALSET_V0_VERSION = 0x00; //!< UBX-CFG-VALSET.version value +static constexpr std::size_t UBX_CFG_VALSET_V0_MIN_SIZE = sizeof(UBX_CFG_VALSET_V0_GROUP0); //!< @todo documentation +static constexpr uint8_t UBX_CFG_VALSET_V0_LAYERS_RAM = 0x01; //!< UBX-CFG-VALSET.layers flag: layer RAM +static constexpr uint8_t UBX_CFG_VALSET_V0_LAYERS_BBR = 0x02; //!< UBX-CFG-VALSET.layers flag: layer BBR +static constexpr uint8_t UBX_CFG_VALSET_V0_LAYERS_FLASH = 0x04; //!< UBX-CFG-VALSET.layers flag: layer Flash +static constexpr uint8_t UBX_CFG_VALSET_V0_RESERVED = 0x00; //!< UBX-CFG-VALSET.reserved value +static constexpr std::size_t UBX_CFG_VALSET_V0_MAX_KV = 64; //!< UBX-CFG-VALSET.cfgData: maximum number of key-value pairs +static constexpr std::size_t UBX_CFG_VALSET_V0_CFGDATA_MAX_SIZE = UBX_CFG_VALSET_V0_MAX_KV * (4 + 8); //!< UBX-CFG-VALSET.cfgData maximum size +static constexpr std::size_t UBX_CFG_VALSET_V0_MAX_SIZE = sizeof(UBX_CFG_VALSET_V0_GROUP0) + UBX_CFG_VALSET_V0_CFGDATA_MAX_SIZE + UBX_FRAME_SIZE; //!< @todo documentation + +static constexpr uint8_t UBX_CFG_VALSET_V1_VERSION = 0x01; //!< UBX-CFG-VALSET.version value +static constexpr std::size_t UBX_CFG_VALSET_V1_MIN_SIZE = sizeof(UBX_CFG_VALSET_V1_GROUP0); //!< @todo documentation +static constexpr uint8_t UBX_CFG_VALSET_V1_LAYERS_RAM = 0x01; //!< UBX-CFG-VALSET.layers flag: layer RAM +static constexpr uint8_t UBX_CFG_VALSET_V1_LAYERS_BBR = 0x02; //!< UBX-CFG-VALSET.layers flag: layer BBR +static constexpr uint8_t UBX_CFG_VALSET_V1_LAYERS_FLASH = 0x04; //!< UBX-CFG-VALSET.layers flag: layer Flash +static constexpr uint8_t UBX_CFG_VALSET_V1_TRANSACTION_NONE = 0; //!< UBX-CFG-VALSET.transaction value: no transaction +static constexpr uint8_t UBX_CFG_VALSET_V1_TRANSACTION_BEGIN = 1; //!< UBX-CFG-VALSET.transaction value: transaction begin +static constexpr uint8_t UBX_CFG_VALSET_V1_TRANSACTION_CONTINUE = 2; //!< UBX-CFG-VALSET.transaction value: transaction continue +static constexpr uint8_t UBX_CFG_VALSET_V1_TRANSACTION_END = 3; //!< UBX-CFG-VALSET.transaction value: transaction: end +static constexpr uint8_t UBX_CFG_VALSET_V1_RESERVED = 0x00; //!< UBX-CFG-VALSET.reserved value +static constexpr std::size_t UBX_CFG_VALSET_V1_MAX_KV = 64; //!< UBX-CFG-VALSET.cfgData: maximum number of key-value pairs +static constexpr std::size_t UBX_CFG_VALSET_V1_CFGDATA_MAX_SIZE = UBX_CFG_VALSET_V1_MAX_KV * (4 + 8); //!< UBX-CFG-VALSET.cfgData maximum size +static constexpr std::size_t UBX_CFG_VALSET_V1_MAX_SIZE = sizeof(UBX_CFG_VALSET_V1_GROUP0) + UBX_CFG_VALSET_V1_CFGDATA_MAX_SIZE + UBX_FRAME_SIZE; //!< @todo documentation +// clang-format on + +///@} +// --------------------------------------------------------------------------------------------------------------------- +/** + * @name UBX-CFG-VALGET message + * @{ + */ + +//! UBX-CFG-VALGET (version 0, poll) message payload header +struct UBX_CFG_VALGET_V0_GROUP0 // clang-format off +{ + uint8_t version; //!< Message version (#UBX_CFG_VALGET_V0_VERSION) + uint8_t layer; //!< Configuration layer + uint16_t position; //!< Number of values to skip in result set +}; // clang-format on + +static_assert(sizeof(UBX_CFG_VALGET_V0_GROUP0) == 4, ""); + +//! UBX-CFG-VALGET (version 1, output) message payload header +struct UBX_CFG_VALGET_V1_GROUP0 // clang-format off +{ + uint8_t version; //!< Message version (#UBX_CFG_VALGET_V1_VERSION) + uint8_t layer; //!< Configuration layer + uint16_t position; //!< Number of values to skip in result set +}; // clang-format on + +static_assert(sizeof(UBX_CFG_VALGET_V1_GROUP0) == 4, ""); + +// clang-format off +static constexpr uint8_t UBX_CFG_VALGET_VERSION_GET(const uint8_t* msg) { return msg[UBX_HEAD_SIZE]; } //!< @todo documentation + +static constexpr uint8_t UBX_CFG_VALGET_V0_VERSION = 0x00; //!< UBX-CFG-VALGET.version value +static constexpr std::size_t UBX_CFG_VALGET_V0_MIN_SIZE = sizeof(UBX_CFG_VALGET_V0_GROUP0); //!< @todo documentation +static constexpr uint8_t UBX_CFG_VALGET_V0_LAYER_RAM = 0; //!< UBX-CFG-VALGET.layers value: layer RAM +static constexpr uint8_t UBX_CFG_VALGET_V0_LAYER_BBR = 1; //!< UBX-CFG-VALGET.layers value: layer BBR +static constexpr uint8_t UBX_CFG_VALGET_V0_LAYER_FLASH = 2; //!< UBX-CFG-VALGET.layers value: layer Flash +static constexpr uint8_t UBX_CFG_VALGET_V0_LAYER_DEFAULT = 7; //!< UBX-CFG-VALGET.layers value: layer Default +static constexpr std::size_t UBX_CFG_VALGET_V0_MAX_K = 64; //!< UBX-CFG-VALGET.cfgData maximum number of keys +static constexpr std::size_t UBX_CFG_VALGET_V0_KEYS_MAX_SIZE = UBX_CFG_VALGET_V0_MAX_K * 4; //!< UBX-CFG-VALGET.keys maximum size +static constexpr uint32_t UBX_CFG_VALGET_V0_GROUP_WILDCARD(const uint32_t groupId) { return groupId | 0x0000ffff; } //!< UBX-CFG-VALGET.keys group wildcard +static constexpr uint32_t UBX_CFG_VALGET_V0_ALL_WILDCARD = 0x0fffffff; //!< UBX-CFG-VALGET.keys all wildcard +static constexpr std::size_t UBX_CFG_VALGET_V0_MAX_SIZE = sizeof(UBX_CFG_VALGET_V0_GROUP0) + UBX_CFG_VALGET_V0_KEYS_MAX_SIZE + UBX_FRAME_SIZE; //!< @todo documentation + +static constexpr uint8_t UBX_CFG_VALGET_V1_VERSION = 0x01; //!< UBX-CFG-VALGET.version value +static constexpr std::size_t UBX_CFG_VALGET_V1_MIN_SIZE = sizeof(UBX_CFG_VALGET_V1_GROUP0); //!< @todo documentation +static constexpr uint8_t UBX_CFG_VALGET_V1_LAYER_RAM = 0; //!< UBX-CFG-VALGET.layers value: layer RAM +static constexpr uint8_t UBX_CFG_VALGET_V1_LAYER_BBR = 1; //!< UBX-CFG-VALGET.layers value: layer BBR +static constexpr uint8_t UBX_CFG_VALGET_V1_LAYER_FLASH = 2; //!< UBX-CFG-VALGET.layers value: layer Flash +static constexpr uint8_t UBX_CFG_VALGET_V1_LAYER_DEFAULT = 7; //!< UBX-CFG-VALGET.layers value: layer Default +static constexpr std::size_t UBX_CFG_VALGET_V1_MAX_KV = 64; //!< UBX-CFG-VALGET.cfgData maximum number of keys +static constexpr std::size_t UBX_CFG_VALGET_V1_CFGDATA_MAX_SIZE = UBX_CFG_VALGET_V1_MAX_KV * (4 + 8); //!< UBX-CFG-VALGET.keys maximum size +static constexpr uint32_t UBX_CFG_VALGET_V1_GROUP_WILDCARD(const uint32_t groupId) { return groupId | 0x0000ffff; } //!< UBX-CFG-VALGET.keys group wildcard +static constexpr uint32_t UBX_CFG_VALGET_V1_ALL_WILDCARD = 0x0fffffff; //!< UBX-CFG-VALGET.keys all wildcard +static constexpr std::size_t UBX_CFG_VALGET_V1_MAX_SIZE = sizeof(UBX_CFG_VALGET_V1_GROUP0) + UBX_CFG_VALGET_V1_CFGDATA_MAX_SIZE + UBX_FRAME_SIZE; //!< @todo documentation +// clang-format on + +///@} +// --------------------------------------------------------------------------------------------------------------------- +/** + * @name UBX-CFG-VALDEL message + * @{ + */ + +//! UBX-CFG-VALDEL (version 1, input) message payload header +struct UBX_CFG_VALDEL_V1_GROUP0 // clang-format off +{ + uint8_t version; //!< Message version (#UBX_CFG_VALGET_V1_VERSION) + uint8_t layers; //!< Configuration layers + uint8_t transaction; //!< Transaction mode + uint8_t reserved; //!< Reserved (set to 0x00) +}; // clang-format on + +static_assert(sizeof(UBX_CFG_VALDEL_V1_GROUP0) == 4, ""); + +// clang-format off +static constexpr uint8_t UBX_CFG_VALDEL_VERSION_GET(const uint8_t* msg) { return msg[UBX_HEAD_SIZE]; } //!< @todo documentation +static constexpr uint8_t UBX_CFG_VALDEL_V1_VERSION = 0x01; //!< UBX-CFG-VALDEL.version value +static constexpr uint8_t UBX_CFG_VALDEL_V1_LAYER_BBR = 0x02; //!< UBX-CFG-VALDEL.layers flag: layer BBR +static constexpr uint8_t UBX_CFG_VALDEL_V1_LAYER_FLASH = 0x04; //!< UBX-CFG-VALDEL.layers flag: layer Flash +static constexpr uint8_t UBX_CFG_VALDEL_V1_TRANSACTION_NONE = 0; //!< UBX-CFG-VALDEL.transaction value: no transaction +static constexpr uint8_t UBX_CFG_VALDEL_V1_TRANSACTION_BEGIN = 1; //!< UBX-CFG-VALDEL.transaction value: transaction begin +static constexpr uint8_t UBX_CFG_VALDEL_V1_TRANSACTION_CONTINUE = 2; //!< UBX-CFG-VALDEL.transaction value: transaction continue +static constexpr uint8_t UBX_CFG_VALDEL_V1_TRANSACTION_END = 3; //!< UBX-CFG-VALDEL.transaction value: transaction: end +static constexpr uint8_t UBX_CFG_VALDEL_V1_RESERVED = 0x00; //!< UBX-CFG-VALDEL.reserved value +static constexpr std::size_t UBX_CFG_VALDEL_V1_MAX_K = 64; //!< UBX-CFG-VALSET.cfgData maximum number of key IDs +static constexpr std::size_t UBX_CFG_VALDEL_V1_KEYS_MAX_SIZE = UBX_CFG_VALDEL_V1_MAX_K * 4; //!< UBX-CFG-VALDEL.keys maximum size +static constexpr std::size_t UBX_CFG_VALDEL_V1_MAX_SIZE = sizeof(UBX_CFG_VALDEL_V1_GROUP0) + UBX_CFG_VALDEL_V1_KEYS_MAX_SIZE + UBX_FRAME_SIZE; //!< @todo documentation +// clang-format on + +///@} +// --------------------------------------------------------------------------------------------------------------------- +/** + * @name UBX-CFG-RST message + * @{ + */ + +//! UBX-CFG-RST (version 0, command) message payload +struct UBX_CFG_RST_V0_GROUP0 // clang-format off +{ + uint16_t navBbrMask; //!< BBR sections to clear + uint8_t resetMode; //!< Reset type + uint8_t reserved; //!< Reserved +}; // clang-format on + +static_assert(sizeof(UBX_CFG_RST_V0_GROUP0) == 4, ""); + +// clang-format off +static constexpr std::size_t UBX_CFG_RST_V0_SIZE = sizeof(UBX_CFG_RST_V0_GROUP0) + UBX_FRAME_SIZE; //!< @todo documentation +static constexpr uint16_t UBX_CFG_RST_V0_NAVBBR_NONE = 0x0001; //!< Nothing +static constexpr uint16_t UBX_CFG_RST_V0_NAVBBR_EPH = 0x0001; //!< Ephemeris +static constexpr uint16_t UBX_CFG_RST_V0_NAVBBR_ALM = 0x0002; //!< Almanac +static constexpr uint16_t UBX_CFG_RST_V0_NAVBBR_HEALTH = 0x0004; //!< Health +static constexpr uint16_t UBX_CFG_RST_V0_NAVBBR_KLOB = 0x0008; //!< Klobuchar parameters +static constexpr uint16_t UBX_CFG_RST_V0_NAVBBR_POS = 0x0010; //!< Position +static constexpr uint16_t UBX_CFG_RST_V0_NAVBBR_CLKD = 0x0020; //!< Clock drift +static constexpr uint16_t UBX_CFG_RST_V0_NAVBBR_OSC = 0x0040; //!< Oscillator parameters +static constexpr uint16_t UBX_CFG_RST_V0_NAVBBR_UTC = 0x0080; //!< UTC and leap second parameters +static constexpr uint16_t UBX_CFG_RST_V0_NAVBBR_RTC = 0x0100; //!< RTC +static constexpr uint16_t UBX_CFG_RST_V0_NAVBBR_AOP = 0x8000; //!< AssistNow Autonomous +static constexpr uint16_t UBX_CFG_RST_V0_NAVBBR_HOTSTART = 0x0000; //!< Hostsart (keep all data) +static constexpr uint16_t UBX_CFG_RST_V0_NAVBBR_WARMSTART = 0x0001; //!< Warmstart (clear ephemerides) +static constexpr uint16_t UBX_CFG_RST_V0_NAVBBR_COLDSTART = 0xffff; //!< Coldstart (erase all data) +static constexpr uint8_t UBX_CFG_RST_V0_RESETMODE_HW_FORCED = 0x00; //!< Forced, immediate hardware reset +static constexpr uint8_t UBX_CFG_RST_V0_RESETMODE_SW = 0x01; //!< Controlled software reset +static constexpr uint8_t UBX_CFG_RST_V0_RESETMODE_GNSS = 0x02; //!< Restart GNSS +static constexpr uint8_t UBX_CFG_RST_V0_RESETMODE_HW_CONTROLLED = 0x04; //!< Controlled hardware reset +static constexpr uint8_t UBX_CFG_RST_V0_RESETMODE_GNSS_STOP = 0x08; //!< Stop GNSS +static constexpr uint8_t UBX_CFG_RST_V0_RESETMODE_GNSS_START = 0x09; //!< Start GNSS +static constexpr uint8_t UBX_CFG_RST_V0_RESERVED = 0x00; //!< Reserved +// clang-format on + +///@} +// --------------------------------------------------------------------------------------------------------------------- +/** + * @name UBX-CFG-CFG message + * @{ + */ + +//! UBX-CFG-CFG (version 0, command) message head +struct UBX_CFG_CFG_V0_GROUP0 // clang-format off +{ + uint32_t clearMask; //!< @todo documentation + uint32_t saveMask; //!< @todo documentation + uint32_t loadMask; //!< @todo documentation +}; // clang-format on + +static_assert(sizeof(UBX_CFG_CFG_V0_GROUP0) == 12, ""); + +//! UBX-CFG-CFG (version 0, command) message optional group +struct UBX_PACKED UBX_CFG_CFG_V0_GROUP1 // clang-format off +{ + uint8_t deviceMask; //!< @todo documentation +};// clang-format off + +static_assert(sizeof(UBX_CFG_CFG_V0_GROUP1) == 1, ""); + +// clang-format off +static constexpr std::size_t UBX_CFG_CFG_V0_MIN_SIZE = sizeof(UBX_CFG_CFG_V0_GROUP0) + UBX_FRAME_SIZE; //!< @todo documentation +static constexpr std::size_t UBX_CFG_CFG_V0_MAX_SIZE = UBX_CFG_CFG_V0_MIN_SIZE + sizeof(UBX_CFG_CFG_V0_GROUP1); //!< @todo documentation +static constexpr uint32_t UBX_CFG_CFG_V0_CLEAR_NONE = 0x00000000; //!< Clear no config +static constexpr uint32_t UBX_CFG_CFG_V0_CLEAR_ALL = 0xffffffff; //!< Clear all config +static constexpr uint32_t UBX_CFG_CFG_V0_SAVE_NONE = 0x00000000; //!< Save no config +static constexpr uint32_t UBX_CFG_CFG_V0_SAVE_ALL = 0xffffffff; //!< Save all config +static constexpr uint32_t UBX_CFG_CFG_V0_LOAD_NONE = 0x00000000; //!< Load no config +static constexpr uint32_t UBX_CFG_CFG_V0_LOAD_ALL = 0xffffffff; //!< Load all config +static constexpr uint8_t UBX_CFG_CFG_V0_DEVICE_BBR = 0x01; //!< Layer BBR +static constexpr uint8_t UBX_CFG_CFG_V0_DEVICE_FLASH = 0x02; //!< Layer Flash +// clang-format on + +///@} +// --------------------------------------------------------------------------------------------------------------------- +/** + * @name UBX-ESF-MEAS message + * @{ + */ + +//! UBX-ESF-MEAS (version 0, input and output) message head +struct UBX_ESF_MEAS_V0_GROUP0 // clang-format off +{ + uint32_t timeTag; //!< @todo documentation + uint16_t flags; //!< @todo documentation + uint16_t id; //!< @todo documentation +}; // clang-format on + +static_assert(sizeof(UBX_ESF_MEAS_V0_GROUP0) == 8, ""); + +//! UBX-ESF-MEAS (version 0, input and output) data +struct UBX_ESF_MEAS_V0_GROUP1 // clang-format off +{ + uint32_t data; //!< @todo documentation +}; // clang-format on + +static_assert(sizeof(UBX_ESF_MEAS_V0_GROUP1) == 4, ""); + +//! UBX-ESF-MEAS (version 0, input and output) timetag +struct UBX_ESF_MEAS_V0_GROUP2 // clang-format off +{ + uint32_t calibTtag; //!< @todo documentation +}; // clang-format on + +static_assert(sizeof(UBX_ESF_MEAS_V0_GROUP2) == 4, ""); + +// clang-format off +static constexpr std::size_t UBX_ESF_MEAS_V0_MIN_SIZE = sizeof(UBX_ESF_MEAS_V0_GROUP0) + UBX_FRAME_SIZE; //!< @todo documentation +static constexpr uint8_t UBX_ESF_MEAS_V0_FLAGS_TIMEMARKSENT_GET(const uint16_t flags) { return flags & 0x03; } //!< @todo documentation +static constexpr uint8_t UBX_ESF_MEAS_V0_FLAGS_TIMEMARKSENT_NONE = 0; //!< @todo documentation +static constexpr uint8_t UBX_ESF_MEAS_V0_FLAGS_TIMEMARKSENT_EXT0 = 1; //!< @todo documentation +static constexpr uint8_t UBX_ESF_MEAS_V0_FLAGS_TIMEMARKSENT_EXT1 = 2; //!< @todo documentation +static constexpr bool UBX_ESF_MEAS_V0_FLAGS_CALIBTTAGVALID(const uint16_t flags) { return (flags & 0x0008) == 0x0008; } //!< @todo documentation +static constexpr std::size_t UBX_ESF_MEAS_V0_FLAGS_NUMMEAS_GET(const uint16_t flags) { return (flags >> 11) & 0x1f; } //!< @todo documentation +static constexpr uint32_t UBX_ESF_MEAS_V0_DATA_DATAFIELD_GET(const uint32_t data) { return data & 0x00ffffff; } //!< @todo documentation +static constexpr uint8_t UBX_ESF_MEAS_V0_DATA_DATATYPE_GET(const uint32_t data) { return (data >> 24) & 0x0000003f; } //!< same enum as UBX-ESF-STATUS.type it seems +static constexpr double UBX_ESF_MEAS_V0_CALIBTTAG_SCALE = 1e-3; //!< @todo documentation +static constexpr std::size_t UBX_ESF_MEAS_V0_SIZE(const uint8_t* msg) { return /* argh.. nice message design! */ \ + sizeof(UBX_ESF_MEAS_V0_GROUP0) + UBX_FRAME_SIZE + (UBX_ESF_MEAS_V0_FLAGS_NUMMEAS_GET(*((uint16_t *)&((uint8_t *)(msg))[UBX_HEAD_SIZE + 4])) * sizeof(UBX_ESF_MEAS_V0_GROUP1)) + + UBX_ESF_MEAS_V0_FLAGS_CALIBTTAGVALID(*((uint16_t *)&((uint8_t *)(msg))[UBX_HEAD_SIZE + 4])) ? sizeof(UBX_ESF_MEAS_V0_GROUP2) : 0; } //!< @todo documentation +// clang-format on + +///@} +// --------------------------------------------------------------------------------------------------------------------- +/** + * @name UBX-ESF-STATUS message + * @{ + */ + +//! UBX-ESF-STATUS (version 0, output) message head +struct UBX_ESF_STATUS_V2_GROUP0 // clang-format off +{ + uint32_t iTOW; //!< @todo documentation + uint8_t version; //!< @todo documentation + uint8_t initStatus1; //!< @todo documentation + uint8_t initStatus2; //!< @todo documentation + uint8_t reserved0[5]; //!< @todo documentation + uint8_t fusionMode; //!< @todo documentation + uint8_t reserved1[2]; //!< @todo documentation + uint8_t numSens; //!< @todo documentation +}; // clang-format on + +static_assert(sizeof(UBX_ESF_STATUS_V2_GROUP0) == 16, ""); + +//! UBX-ESF-STATUS (version 0, output) per-sensor status +struct UBX_ESF_STATUS_V2_GROUP1 // clang-format off +{ + uint8_t sensStatus1; //!< @todo documentation + uint8_t sensStatus2; //!< @todo documentation + uint8_t freq; //!< @todo documentation + uint8_t faults; //!< @todo documentation +}; // clang-format on + +static_assert(sizeof(UBX_ESF_STATUS_V2_GROUP1) == 4, ""); + +// clang-format off +static constexpr uint8_t UBX_ESF_STATUS_VERSION_GET(const uint8_t* msg) { return msg[UBX_HEAD_SIZE + 4]; } //!< @todo documentation +static constexpr uint8_t UBX_ESF_STATUS_V2_VERSION = 0x02; //!< @todo documentation +static constexpr std::size_t UBX_ESF_STATUS_V2_MIN_SIZE = sizeof(UBX_ESF_STATUS_V2_GROUP0) + UBX_FRAME_SIZE; //!< @todo documentation +static constexpr std::size_t UBX_ESF_STATUS_V2_SIZE(const uint8_t* msg) { return //!< @todo documentation + sizeof(UBX_ESF_STATUS_V2_GROUP0) + UBX_FRAME_SIZE + (((uint8_t *)(msg))[UBX_HEAD_SIZE + 15] * sizeof(UBX_ESF_STATUS_V2_GROUP1)); } //!< @todo documentation +static constexpr double UBX_ESF_STATUS_V2_ITOW_SCALE = 1e-3; //!< @todo documentation +static constexpr uint8_t UBX_ESF_STATUS_V2_INITSTATUS1_WTINITSTATUS_GET(const uint8_t initStatus1) { return initStatus1 & 0x03; } //!< @todo documentation +static constexpr uint8_t UBX_ESF_STATUS_V2_INITSTATUS1_WTINITSTATUS_OFF = 0; //!< @todo documentation +static constexpr uint8_t UBX_ESF_STATUS_V2_INITSTATUS1_WTINITSTATUS_INITALIZING = 1; //!< @todo documentation +static constexpr uint8_t UBX_ESF_STATUS_V2_INITSTATUS1_WTINITSTATUS_INITIALIZED = 2; //!< @todo documentation +static constexpr uint8_t UBX_ESF_STATUS_V2_INITSTATUS1_MNTALGSTATUS_GET(const uint8_t initStatus1) { return (initStatus1 >> 2) & 0x07; } //!< @todo documentation +static constexpr uint8_t UBX_ESF_STATUS_V2_INITSTATUS1_MNTALGSTATUS_OFF = 0; //!< @todo documentation +static constexpr uint8_t UBX_ESF_STATUS_V2_INITSTATUS1_MNTALGSTATUS_INITALIZING = 1; //!< @todo documentation +static constexpr uint8_t UBX_ESF_STATUS_V2_INITSTATUS1_MNTALGSTATUS_INITIALIZED1 = 2; //!< @todo documentation +static constexpr uint8_t UBX_ESF_STATUS_V2_INITSTATUS1_MNTALGSTATUS_INITIALIZED2 = 3; //!< @todo documentation +static constexpr uint8_t UBX_ESF_STATUS_V2_INITSTATUS1_INSINITSTATUS_GET(const uint8_t initStatus1){ return (initStatus1 >> 5) & 0x07; } //!< @todo documentation +static constexpr uint8_t UBX_ESF_STATUS_V2_INITSTATUS1_INSINITSTATUS_OFF = 0; //!< @todo documentation +static constexpr uint8_t UBX_ESF_STATUS_V2_INITSTATUS1_INSINITSTATUS_INITALIZING = 1; //!< @todo documentation +static constexpr uint8_t UBX_ESF_STATUS_V2_INITSTATUS1_INSINITSTATUS_INITIALIZED1 = 2; //!< @todo documentation +static constexpr uint8_t UBX_ESF_STATUS_V2_INITSTATUS1_INSINITSTATUS_INITIALIZED2 = 3; //!< @todo documentation +static constexpr uint8_t UBX_ESF_STATUS_V2_INITSTATUS2_IMUINITSTATUS_GET(const uint8_t initStatus2){ return initStatus2 & 0x03; } //!< @todo documentation +static constexpr uint8_t UBX_ESF_STATUS_V2_INITSTATUS2_IMUINITSTATUS_OFF = 0; //!< @todo documentation +static constexpr uint8_t UBX_ESF_STATUS_V2_INITSTATUS2_IMUINITSTATUS_INITALIZING = 1; //!< @todo documentation +static constexpr uint8_t UBX_ESF_STATUS_V2_INITSTATUS2_IMUINITSTATUS_INITIALIZED1 = 2; //!< @todo documentation +static constexpr uint8_t UBX_ESF_STATUS_V2_INITSTATUS2_IMUINITSTATUS_INITIALIZED2 = 3; //!< @todo documentation +static constexpr uint8_t UBX_ESF_STATUS_V2_FUSIONMODE_INIT = 0x00; //!< @todo documentation +static constexpr uint8_t UBX_ESF_STATUS_V2_FUSIONMODE_FUSION = 0x01; //!< @todo documentation +static constexpr uint8_t UBX_ESF_STATUS_V2_FUSIONMODE_SUSPENDED = 0x02; //!< @todo documentation +static constexpr uint8_t UBX_ESF_STATUS_V2_FUSIONMODE_DISABLED = 0x03; //!< @todo documentation +static constexpr uint8_t UBX_ESF_STATUS_V2_SENSSTATUS1_TYPE_GET(const uint8_t sensStatus1) { return sensStatus1 & 0x3f; } //!< same enum as UBX-ESF-MEAS.dataType it seems //!< @todo documentation +static constexpr uint8_t UBX_ESF_STATUS_V2_SENSSTATUS1_USED = 0x40; //!< @todo documentation +static constexpr uint8_t UBX_ESF_STATUS_V2_SENSSTATUS1_READY = 0x80; //!< @todo documentation +static constexpr uint8_t UBX_ESF_STATUS_V2_SENSSTATUS2_CALIBSTATUS_GET(const uint8_t sensStatus2) { return sensStatus2 & 0x03; } //!< @todo documentation +static constexpr uint8_t UBX_ESF_STATUS_V2_SENSSTATUS2_CALIBSTATUS_NOTCALIB = 0; //!< @todo documentation +static constexpr uint8_t UBX_ESF_STATUS_V2_SENSSTATUS2_CALIBSTATUS_CALIBRATING = 1; //!< @todo documentation +static constexpr uint8_t UBX_ESF_STATUS_V2_SENSSTATUS2_CALIBSTATUS_CALIBRATED1 = 2; //!< @todo documentation +static constexpr uint8_t UBX_ESF_STATUS_V2_SENSSTATUS2_CALIBSTATUS_CALIBRATED2 = 3; //!< @todo documentation +static constexpr uint8_t UBX_ESF_STATUS_V2_SENSSTATUS2_TIMESTATUS_GET(const uint8_t sensStatus2) { return (sensStatus2 >> 2) & 0x03; } //!< @todo documentation +static constexpr uint8_t UBX_ESF_STATUS_V2_SENSSTATUS2_TIMESTATUS_NODATA = 0; //!< @todo documentation +static constexpr uint8_t UBX_ESF_STATUS_V2_SENSSTATUS2_TIMESTATUS_FIRSTBYTE = 1; //!< @todo documentation +static constexpr uint8_t UBX_ESF_STATUS_V2_SENSSTATUS2_TIMESTATUS_EVENT = 2; //!< @todo documentation +static constexpr uint8_t UBX_ESF_STATUS_V2_SENSSTATUS2_TIMESTATUS_TIMETAG = 3; //!< @todo documentation +static constexpr uint8_t UBX_ESF_STATUS_V2_FAULTS_BADMEAS = 0x01; //!< @todo documentation +static constexpr uint8_t UBX_ESF_STATUS_V2_FAULTS_BADTTAG = 0x02; //!< @todo documentation +static constexpr uint8_t UBX_ESF_STATUS_V2_FAULTS_MISSINGMEAS = 0x04; //!< @todo documentation +static constexpr uint8_t UBX_ESF_STATUS_V2_FAULTS_NOISYMEAS = 0x08; //!< @todo documentation +// clang-format on + +///@} +// --------------------------------------------------------------------------------------------------------------------- +/** + * @name UBX-MON-COMMS message + * @{ + */ + +//! UBX-MON-COMMS (version 0, output) payload head +struct UBX_MON_COMMS_V0_GROUP0 // clang-format off +{ + uint8_t version; //!< @todo documentation + uint8_t nPorts; //!< @todo documentation + uint8_t txErrors; //!< @todo documentation + uint8_t reserved0; //!< @todo documentation + uint8_t protIds[4]; //!< @todo documentation +}; // clang-format on + +static_assert(sizeof(UBX_MON_COMMS_V0_GROUP0) == 8, ""); + +//! UBX-MON-COMMS (version 0, output) payload repeated group +struct UBX_MON_COMMS_V0_GROUP1 // clang-format off +{ + // Similar to UBX-MON-HW3.pinId this seems to be made up of two values actually: + // - a port ID (probably same enum as in u-center's UBX-CFG-PRT: 0 = I2C, 1 = UART1, 2 = UART2, 3 = USB, 4 = SPI) + // - a "bank" of ports (0, 1, ...) + // u-center only shows some of the ports it seems (why?!) + uint16_t portId; //!< @todo documentation + uint16_t txPending; //!< @todo documentation + uint32_t txBytes; //!< @todo documentation + uint8_t txUsage; //!< @todo documentation + uint8_t txPeakUsage; //!< @todo documentation + uint16_t rxPending; //!< @todo documentation + uint32_t rxBytes; //!< @todo documentation + uint8_t rxUsage; //!< @todo documentation + uint8_t rxPeakUsage; //!< @todo documentation + uint16_t overrunErrors; //!< @todo documentation + uint16_t msgs[4]; //!< @todo documentation + uint8_t reserved1[8]; //!< @todo documentation + uint32_t skipped; //!< @todo documentation +}; // clang-format on + +static_assert(sizeof(UBX_MON_COMMS_V0_GROUP1) == 40, ""); + +// clang-format off +static constexpr uint8_t UBX_MON_COMMS_VERSION_GET(const uint8_t* msg) { return msg[UBX_HEAD_SIZE]; } //!< @todo documentation +static constexpr uint8_t UBX_MON_COMMS_V0_VERSION = 0x00; //!< @todo documentation +static constexpr std::size_t UBX_MON_COMMS_V0_MIN_SIZE = sizeof(UBX_MON_COMMS_V0_GROUP0) + UBX_FRAME_SIZE; //!< @todo documentation +static constexpr std::size_t UBX_MON_COMMS_V0_SIZE(const uint8_t* msg) { return //!< @todo documentation + sizeof(UBX_MON_COMMS_V0_GROUP0) + UBX_FRAME_SIZE + (((uint8_t *)(msg))[UBX_HEAD_SIZE + 1] * sizeof(UBX_MON_COMMS_V0_GROUP1)); } //!< @todo documentation +static constexpr bool UBX_MON_COMMS_V0_TXERRORS_MEM(const uint8_t txErrors) { return (txErrors & 0x01) == 0x01; } //!< @todo documentation +static constexpr bool UBX_MON_COMMS_V0_TXERRORS_ALLOC(const uint8_t txErrors) { return (txErrors & 0x02) == 0x02; } //!< @todo documentation +static constexpr uint8_t UBX_MON_COMMS_V0_TXERRORS_OUTPUTPORT_GET(const uint8_t txErrors) { return (txErrors >> 3) & 0x7; } //!< @todo documentation +static constexpr uint8_t UBX_MON_COMMS_V0_TXERRORS_OUTPUTPORT_NA = 0; //!< @todo documentation +static constexpr uint8_t UBX_MON_COMMS_V0_TXERRORS_OUTPUTPORT_I2C = 1; //!< @todo documentation +static constexpr uint8_t UBX_MON_COMMS_V0_TXERRORS_OUTPUTPORT_UART1 = 2; //!< @todo documentation +static constexpr uint8_t UBX_MON_COMMS_V0_TXERRORS_OUTPUTPORT_UART2 = 3; //!< @todo documentation +static constexpr uint8_t UBX_MON_COMMS_V0_TXERRORS_OUTPUTPORT_USB = 4; //!< @todo documentation +static constexpr uint8_t UBX_MON_COMMS_V0_TXERRORS_OUTPUTPORT_SPI = 5; //!< @todo documentation +static constexpr uint8_t UBX_MON_COMMS_V0_PROTIDS_UBX = 0x00; //!< @todo documentation +static constexpr uint8_t UBX_MON_COMMS_V0_PROTIDS_NMEA = 0x01; //!< @todo documentation +static constexpr uint8_t UBX_MON_COMMS_V0_PROTIDS_RAW = 0x03; //!< probably.. see UBX-MON-MSGPP +static constexpr uint8_t UBX_MON_COMMS_V0_PROTIDS_RTCM2 = 0x02; //!< @todo documentation +static constexpr uint8_t UBX_MON_COMMS_V0_PROTIDS_RTCM3 = 0x05; //!< @todo documentation +static constexpr uint8_t UBX_MON_COMMS_V0_PROTIDS_SPARTN = 0x06; //!< @todo documentation +static constexpr uint8_t UBX_MON_COMMS_V0_PROTIDS_OTHER = 0xff; //!< @todo documentation +// clang-format on + +///@} +// --------------------------------------------------------------------------------------------------------------------- +/** + * @name UBX-MON-HW message + * @{ + */ + +//! UBX-MON-HW (version 0, output) +struct UBX_MON_HW_V0_GROUP0 // clang-format off +{ + uint32_t pinSel; //!< @todo documentation + uint32_t pinBank; //!< @todo documentation + uint32_t pinDir; //!< @todo documentation + uint32_t pinVal; //!< @todo documentation + uint16_t noisePerMS; //!< @todo documentation + uint16_t agcCnt; //!< @todo documentation + uint8_t aStatus; //!< @todo documentation + uint8_t aPower; //!< @todo documentation + uint8_t flags; //!< @todo documentation + uint8_t reserved0; //!< @todo documentation + uint32_t usedMask; //!< @todo documentation + uint8_t VP[17]; //!< @todo documentation + uint8_t jamInd; //!< @todo documentation + uint8_t reserved1[2]; //!< @todo documentation + uint32_t pinIrq; //!< @todo documentation + uint32_t pullH; //!< @todo documentation + uint32_t pullL; //!< @todo documentation +}; // clang-format on + +static_assert(sizeof(UBX_MON_HW_V0_GROUP0) == 60, ""); + +// clang-format off +static constexpr std::size_t UBX_MON_HW_V0_SIZE = sizeof(UBX_MON_HW_V0_GROUP0) + UBX_FRAME_SIZE; //!< @todo documentation +static constexpr uint8_t UBX_MON_HW_V0_FLAGS_RTCCALIB = 0x01; //!< @todo documentation +static constexpr uint8_t UBX_MON_HW_V0_FLAGS_SAFEBOOT = 0x02; //!< @todo documentation +static constexpr uint8_t UBX_MON_HW_V0_FLAGS_JAMMINGSTATE_GET(const uint8_t flags) { return (flags >> 2) & 0x03; } //!< @todo documentation +static constexpr uint8_t UBX_MON_HW_V0_FLAGS_JAMMINGSTATE_UNKNOWN = 0x00; //!< @todo documentation +static constexpr uint8_t UBX_MON_HW_V0_FLAGS_JAMMINGSTATE_OK = 0x01; //!< @todo documentation +static constexpr uint8_t UBX_MON_HW_V0_FLAGS_JAMMINGSTATE_WARNING = 0x02; //!< @todo documentation +static constexpr uint8_t UBX_MON_HW_V0_FLAGS_JAMMINGSTATE_CRITICAL = 0x03; //!< @todo documentation +static constexpr uint8_t UBX_MON_HW_V0_FLAGS_XTALABSENT = 0x10; //!< @todo documentation +static constexpr uint8_t UBX_MON_HW_V0_ASTATUS_INIT = 0x00; //!< @todo documentation +static constexpr uint8_t UBX_MON_HW_V0_ASTATUS_UNKNOWN = 0x01; //!< @todo documentation +static constexpr uint8_t UBX_MON_HW_V0_ASTATUS_OK = 0x02; //!< @todo documentation +static constexpr uint8_t UBX_MON_HW_V0_ASTATUS_SHORT = 0x03; //!< @todo documentation +static constexpr uint8_t UBX_MON_HW_V0_ASTATUS_OPEN = 0x04; //!< @todo documentation +static constexpr uint8_t UBX_MON_HW_V0_APOWER_OFF = 0x00; //!< @todo documentation +static constexpr uint8_t UBX_MON_HW_V0_APOWER_ON = 0x01; //!< @todo documentation +static constexpr uint8_t UBX_MON_HW_V0_APOWER_UNKNOWN = 0x02; //!< @todo documentation +static constexpr uint16_t UBX_MON_HW_V0_NOISEPERMS_MAX = 200; //!< This seems to be what u-center uses.. +static constexpr uint16_t UBX_MON_HW_V0_AGCCNT_MAX = 8191; //!< @todo documentation +static constexpr uint8_t UBX_MON_HW_V0_JAMIND_MAX = 255; //!< @todo documentation +// clang-format on + +///@} +// --------------------------------------------------------------------------------------------------------------------- +/** + * @name UBX-MON-HW2 message + * @{ + */ + +//! UBX-MON-HW (version 0, output) payload +struct UBX_MON_HW2_V0_GROUP0 // clang-format off +{ + int8_t ofsI; //!< @todo documentation + uint8_t magI; //!< @todo documentation + int8_t ofsQ; //!< @todo documentation + uint8_t magQ; //!< @todo documentation + uint8_t cfgSource; //!< @todo documentation + uint8_t reserved0[3]; //!< @todo documentation + uint32_t lowLevCfg; //!< @todo documentation + uint8_t reserved1[8]; //!< @todo documentation + uint32_t postStatus; //!< @todo documentation + uint8_t reserved2[3]; //!< @todo documentation +}; // clang-format on + +static_assert(sizeof(UBX_MON_HW2_V0_GROUP0) == 28, ""); + +// clang-format off +static constexpr std::size_t UBX_MON_HW2_V0_SIZE = sizeof(UBX_MON_HW2_V0_GROUP0); //!< @todo documentation+ UBX_FRAME_SIZE +static constexpr uint8_t UBX_MON_HW2_V0_CFGSOURCE_ROM = 114; //!< @todo documentation +static constexpr uint8_t UBX_MON_HW2_V0_CFGSOURCE_OTP = 111; //!< @todo documentation +static constexpr uint8_t UBX_MON_HW2_V0_CFGSOURCE_PIN = 112; //!< @todo documentation +static constexpr uint8_t UBX_MON_HW2_V0_CFGSOURCE_FLASH = 102; //!< @todo documentation +// clang-format on + +///@} +// --------------------------------------------------------------------------------------------------------------------- +/** + * @name UBX-MON-HW3 message + * @{ + */ + +//! UBX-MON-HW3 (version 0, output) payload +struct UBX_MON_HW3_V0_GROUP0 // clang-format off +{ + uint8_t version; //!< @todo documentation + uint8_t nPins; //!< @todo documentation + uint8_t flags; //!< @todo documentation + char hwVersion[10]; //!< @todo documentation + uint8_t reserved0[9]; //!< @todo documentation +}; // clang-format on + +static_assert(sizeof(UBX_MON_HW3_V0_GROUP0) == 22, ""); + +//! UBX-MON-HW3 (version 0, output) payload +struct UBX_PACKED UBX_MON_HW3_V0_GROUP1 // clang-format off +{ + uint16_t pinId; //!< @todo documentation // u-center shows ((pinId & 0xff00) >> 8) | ((pinId & 0x00ff) << 8), seems to be: (pinNo << 8) | pinBank + uint16_t pinMask; //!< @todo documentation + uint8_t VP; //!< @todo documentation + uint8_t reserved1; //!< @todo documentation +}; // clang-format on + +static_assert(sizeof(UBX_MON_HW3_V0_GROUP1) == 6, ""); + +// clang-format off +static constexpr uint8_t UBX_MON_HW3_VERSION_GET(const uint8_t* msg) { return msg[UBX_HEAD_SIZE]; } //!< @todo documentation +static constexpr uint8_t UBX_MON_HW3_V0_VERSION = 0x00; //!< @todo documentation +static constexpr std::size_t UBX_MON_HW3_V0_MIN_SIZE = sizeof(UBX_MON_HW3_V0_GROUP0) + UBX_FRAME_SIZE; //!< @todo documentation +static constexpr std::size_t UBX_MON_HW3_V0_SIZE(const uint8_t* msg) { return //!< @todo documentation + sizeof(UBX_MON_HW3_V0_GROUP0) + UBX_FRAME_SIZE + (((uint8_t*)(msg))[UBX_HEAD_SIZE + 1] * sizeof(UBX_MON_HW3_V0_GROUP1)); } //!< @todo documentation +static constexpr bool UBX_MON_HW3_V0_FLAGS_RTCCALIB(const uint8_t flags) { return (flags & 0x01) == 0x01; } //!< @todo documentation +static constexpr bool UBX_MON_HW3_V0_FLAGS_SAFEBOOT(const uint8_t flags) { return (flags & 0x02) == 0x02; } //!< @todo documentation +static constexpr bool UBX_MON_HW3_V0_FLAGS_XTALABSENT(const uint8_t flags) { return (flags & 0x04) == 0x04; } //!< @todo documentation +static constexpr uint8_t UBX_MON_HW3_V0_PINMASK_PERIPHPIO_GET(const uint16_t pinMask) { return pinMask & 0x01; } //!< @todo documentation +static constexpr uint8_t UBX_MON_HW3_V0_PINMASK_PERIPHPIO_PERIPH = 0; //!< @todo documentation +static constexpr uint8_t UBX_MON_HW3_V0_PINMASK_PERIPHPIO_PIO = 1; //!< @todo documentation +static constexpr uint8_t UBX_MON_HW3_V0_PINMASK_PINBANK_GET(const uint16_t pinMask) { return (pinMask >> 1) & 0x01; } //!< @todo documentation +static constexpr uint8_t UBX_MON_HW3_V0_PINMASK_PINBANK_A = 0; //!< @todo documentation +static constexpr uint8_t UBX_MON_HW3_V0_PINMASK_PINBANK_B = 1; //!< @todo documentation +static constexpr uint8_t UBX_MON_HW3_V0_PINMASK_PINBANK_C = 2; //!< @todo documentation +static constexpr uint8_t UBX_MON_HW3_V0_PINMASK_PINBANK_D = 3; //!< @todo documentation +static constexpr uint8_t UBX_MON_HW3_V0_PINMASK_PINBANK_E = 4; //!< @todo documentation +static constexpr uint8_t UBX_MON_HW3_V0_PINMASK_PINBANK_F = 5; //!< @todo documentation +static constexpr uint8_t UBX_MON_HW3_V0_PINMASK_PINBANK_G = 6; //!< @todo documentation +static constexpr uint8_t UBX_MON_HW3_V0_PINMASK_PINBANK_H = 7; //!< @todo documentation +static constexpr uint8_t UBX_MON_HW3_V0_PINMASK_DIRECTION_GET(const uint16_t pinMask) { return (pinMask >> 4) & 0x01; } //!< @todo documentation +static constexpr uint8_t UBX_MON_HW3_V0_PINMASK_DIRECTION_OUT = 0; //!< @todo documentation +static constexpr uint8_t UBX_MON_HW3_V0_PINMASK_DIRECTION_IN = 1; //!< @todo documentation +static constexpr bool UBX_MON_HW3_V0_PINMASK_VALUE(const uint16_t pinMask) { return (pinMask & 0x0020) == 0x0020; } //!< @todo documentation +static constexpr bool UBX_MON_HW3_V0_PINMASK_VPMANAGER(const uint16_t pinMask) { return (pinMask & 0x0040) == 0x0040; } //!< @todo documentation +static constexpr bool UBX_MON_HW3_V0_PINMASK_PIOIRQ(const uint16_t pinMask) { return (pinMask & 0x0080) == 0x0080; } //!< @todo documentation +static constexpr bool UBX_MON_HW3_V0_PINMASK_PIOPULLHIGH(const uint16_t pinMask) { return (pinMask & 0x0100) == 0x0100; } //!< @todo documentation +static constexpr bool UBX_MON_HW3_V0_PINMASK_PIOPULLLOW(const uint16_t pinMask) { return (pinMask & 0x0200) == 0x0200; } //!< @todo documentation +// clang-format on + +///@} +// --------------------------------------------------------------------------------------------------------------------- +/** + * @name UBX-MON-RF message + * @{ + */ + +//! UBX-MON-RF (version 0, output) payload head +struct UBX_MON_RF_V0_GROUP0 // clang-format off +{ + uint8_t version; //!< @todo documentation + uint8_t nBlocks; //!< @todo documentation + uint8_t reserved[2]; //!< @todo documentation +}; +// clang-format on + +static_assert(sizeof(UBX_MON_RF_V0_GROUP0) == 4, ""); + +//! UBX-MON-RF (version 0, output) payload repeated group +struct UBX_MON_RF_V0_GROUP1 // clang-format off +{ + uint8_t blockId; //!< @todo documentation + uint8_t flags; //!< @todo documentation + uint8_t antStatus; //!< @todo documentation + uint8_t antPower; //!< @todo documentation + uint32_t postStatus; //!< @todo documentation + uint8_t reserved1[4]; //!< @todo documentation + uint16_t noisePerMS; //!< @todo documentation + uint16_t agcCnt; //!< @todo documentation + uint8_t jamInd; //!< @todo documentation + int8_t ofsI; //!< @todo documentation + int8_t magI; //!< @todo documentation + int8_t ofsQ; //!< @todo documentation + int8_t magQ; //!< @todo documentation + uint8_t reserved2[3]; //!< @todo documentation +}; // clang-format on + +static_assert(sizeof(UBX_MON_RF_V0_GROUP1) == 24, ""); + +// clang-format off +static constexpr uint8_t UBX_MON_RF_VERSION_GET(const uint8_t* msg) { return msg[UBX_HEAD_SIZE]; } //!< @todo documentation +static constexpr uint8_t UBX_MON_RF_V0_VERSION = 0x00; //!< @todo documentation +static constexpr std::size_t UBX_MON_RF_V0_MIN_SIZE = sizeof(UBX_MON_RF_V0_GROUP0) + UBX_FRAME_SIZE; //!< @todo documentation +static constexpr uint8_t UBX_MON_RF_V0_FLAGS_JAMMINGSTATE_GET(const uint8_t f) { return f & 0x03; } //!< @todo documentation +static constexpr uint8_t UBX_MON_RF_V0_FLAGS_JAMMINGSTATE_UNKN = 0; //!< @todo documentation +static constexpr uint8_t UBX_MON_RF_V0_FLAGS_JAMMINGSTATE_OK = 1; //!< @todo documentation +static constexpr uint8_t UBX_MON_RF_V0_FLAGS_JAMMINGSTATE_WARN = 2; //!< @todo documentation +static constexpr uint8_t UBX_MON_RF_V0_FLAGS_JAMMINGSTATE_CRIT = 3; //!< @todo documentation +static constexpr uint8_t UBX_MON_RF_V0_ANTSTATUS_INIT = 0; //!< @todo documentation +static constexpr uint8_t UBX_MON_RF_V0_ANTSTATUS_DONTKNOW = 1; //!< @todo documentation +static constexpr uint8_t UBX_MON_RF_V0_ANTSTATUS_OK = 2; //!< @todo documentation +static constexpr uint8_t UBX_MON_RF_V0_ANTSTATUS_SHORT = 3; //!< @todo documentation +static constexpr uint8_t UBX_MON_RF_V0_ANTSTATUS_OPEN = 4; //!< @todo documentation +static constexpr uint8_t UBX_MON_RF_V0_ANTPOWER_OFF = 0; //!< @todo documentation +static constexpr uint8_t UBX_MON_RF_V0_ANTPOWER_ON = 1; //!< @todo documentation +static constexpr uint8_t UBX_MON_RF_V0_ANTPOWER_DONTKNOW = 2; //!< @todo documentation +static constexpr uint16_t UBX_MON_RF_V0_NOISEPERMS_MAX = 200; //!< This seems to be what u-center uses.. +static constexpr uint16_t UBX_MON_RF_V0_AGCCNT_MAX = 8191; //!< @todo documentation +static constexpr uint8_t UBX_MON_RF_V0_JAMIND_MAX = 255; //!< @todo documentation +// clang-format on + +///@} + +// --------------------------------------------------------------------------------------------------------------------- +/** + * @name UBX-MON-SPAN message + * @{ + */ + +//! UBX-MON-RF (version 0, output) payload head +struct UBX_MON_SPAN_V0_GROUP0 // clang-format off +{ + uint8_t version; //!< @todo documentation + uint8_t numRfBlocks; //!< @todo documentation + uint8_t reserved[2]; //!< @todo documentation +}; // clang-format on + +static_assert(sizeof(UBX_MON_SPAN_V0_GROUP0) == 4, ""); + +//! UBX-MON-RF (version 0, output) payload repeated group +struct UBX_MON_SPAN_V0_GROUP1 // clang-format off +{ + uint8_t spectrum[256]; //!< @todo documentation + uint32_t span; //!< @todo documentation + uint32_t res; //!< @todo documentation + uint32_t center; //!< @todo documentation + uint8_t pga; //!< @todo documentation + uint8_t reserved[3]; //!< @todo documentation +}; // clang-format on + +static_assert(sizeof(UBX_MON_SPAN_V0_GROUP1) == 272, ""); + +// clang-format off +static constexpr uint8_t UBX_MON_SPAN_VERSION_GET(const uint8_t* msg) { return msg[UBX_HEAD_SIZE]; } //!< @todo documentation +static constexpr uint8_t UBX_MON_SPAN_V0_VERSION = 0x00; //!< @todo documentation +static constexpr std::size_t UBX_MON_SPAN_V0_MIN_SIZE = sizeof(UBX_MON_SPAN_V0_GROUP0) + UBX_FRAME_SIZE; //!< @todo documentation +static constexpr std::size_t UBX_MON_SPAN_V0_SIZE(const uint8_t* msg) { return + sizeof(UBX_MON_SPAN_V0_GROUP0) + UBX_FRAME_SIZE + (((uint8_t *)(msg))[UBX_HEAD_SIZE + 1] * sizeof(UBX_MON_SPAN_V0_GROUP1)); } //!< @todo documentation +static constexpr double UBX_MON_SPAN_BIN_CENT_FREQ(const uint32_t center, const uint32_t span, const int ix) { return + (double)center + ((double)span * (((double)(ix) - 128.0) / 256.0)); } //!< @todo documentation +// clang-format on + +///@} +// --------------------------------------------------------------------------------------------------------------------- +/** + * @name UBX-MON-TEMP message + * @{ + */ + +//! UBX-MON-TEMP (version 0, output) message payload (no docu available, but u-center shows it...) +struct UBX_MON_TEMP_V0_GROUP0 // clang-format off +{ + uint8_t version; //!< probably version.. @todo documentation + uint8_t reserved0[3]; //!< @todo documentation + int16_t temperature; //!< @todo documentation + uint8_t unknown; //!< unit? 1 = C? @todo documentation + uint8_t reserved1[5]; //!< @todo documentation +}; // clang-format on + +static_assert(sizeof(UBX_MON_TEMP_V0_GROUP0) == 12, ""); + +// clang-format off +static constexpr uint8_t UBX_MON_TEMP_VERSION_GET(const uint8_t* msg) { return msg[UBX_HEAD_SIZE]; } //!< @todo documentation +static constexpr uint8_t UBX_MON_TEMP_V0_VERSION = 0x00; //!< @todo documentation +static constexpr std::size_t UBX_MON_TEMP_V0_SIZE = sizeof(UBX_MON_TEMP_V0_GROUP0) + UBX_FRAME_SIZE; //!< @todo documentation +// clang-format on + +///@} +// --------------------------------------------------------------------------------------------------------------------- +/** + * @name UBX-MON-VER message + * @{ + */ +//! UBX-MON-VER (version 0, output) message payload header +struct UBX_MON_VER_V0_GROUP0 // clang-format off +{ + char swVersion[30]; //!< @todo documentation + char hwVersion[10]; //!< @todo documentation +}; // clang-format on + +static_assert(sizeof(UBX_MON_VER_V0_GROUP0) == 40, ""); + +//! UBX-MON-VER (version 0, output) optional repeated field +struct UBX_MON_VER_V0_GROUP1 // clang-format off +{ + char extension[30]; //!< @todo documentation +}; // clang-format on + +static_assert(sizeof(UBX_MON_VER_V0_GROUP1) == 30, ""); + +// clang-format off +static constexpr uint8_t UBX_MON_VER_V0_MIN_SIZE = sizeof(UBX_MON_VER_V0_GROUP0) + UBX_FRAME_SIZE; //!< @todo documentation +// clang-format on + +///@} +// --------------------------------------------------------------------------------------------------------------------- +/** + * @name UBX-NAV-ATT message + * @{ + */ + +//! UBX-NAV-ATT (version 0, output) payload +struct UBX_NAV_ATT_V0_GROUP0 // clang-format off +{ + uint32_t iTOW; //!< @todo documentation + uint8_t version; //!< @todo documentation + uint8_t reserved0[3]; //!< @todo documentation + int32_t roll; //!< @todo documentation + int32_t pitch; //!< @todo documentation + int32_t heading; //!< @todo documentation + uint32_t accRoll; //!< @todo documentation + uint32_t accPitch; //!< @todo documentation + uint32_t accHeading; //!< @todo documentation +}; // clang-format on + +static_assert(sizeof(UBX_NAV_ATT_V0_GROUP0) == 32, ""); + +// clang-format off +static constexpr uint8_t UBX_NAV_ATT_VERSION_GET(const uint8_t* msg) { return msg[UBX_HEAD_SIZE + sizeof(uint32_t)]; } //!< @todo documentation +static constexpr uint8_t UBX_NAV_ATT_V0_VERSION = 0x00; //!< @todo documentation +static constexpr std::size_t UBX_NAV_ATT_V0_SIZE = sizeof(UBX_NAV_ATT_V0_GROUP0) + UBX_FRAME_SIZE; //!< @todo documentation +static constexpr double UBX_NAV_ATT_V0_ITOW_SCALE = 1e-3; //!< @todo documentation +static constexpr double UBX_NAV_ATT_V0_RPH_SCALING = 1e-5; //!< @todo documentation +// clang-format on + +///@} +// --------------------------------------------------------------------------------------------------------------------- +/** + * @name UBX-NAV-CLOCK message + * @{ + */ + +//! UBX-NAV-CLOCK payload +struct UBX_NAV_CLOCK_V0_GROUP0 // clang-format off +{ + uint32_t iTow; //!< @todo documentation + int32_t clkB; //!< @todo documentation + int32_t clkD; //!< @todo documentation + uint32_t tAcc; //!< @todo documentation + uint32_t fAcc; //!< @todo documentation +}; // clang-format on + +static_assert(sizeof(UBX_NAV_CLOCK_V0_GROUP0) == 20, ""); + +// clang-format off +static constexpr std::size_t UBX_NAV_CLOCK_V0_SIZE = sizeof(UBX_NAV_CLOCK_V0_GROUP0) + UBX_FRAME_SIZE; //!< @todo documentation +static constexpr double UBX_NAV_CLOCK_V0_CLKB_SCALE = 1e-9; //!< @todo documentation +static constexpr double UBX_NAV_CLOCK_V0_CLKD_SCALE = 1e-9; //!< @todo documentation +static constexpr double UBX_NAV_CLOCK_V0_TACC_SCALE = 1e-9; //!< @todo documentation +static constexpr double UBX_NAV_CLOCK_V0_FACC_SCALE = 1e-12; //!< @todo documentation +// clang-format on + +///@} +// --------------------------------------------------------------------------------------------------------------------- +/** + * @name UBX-NAV-COV message + * @{ + */ + +//! UBX-NAV-COV (version 0, output) payload head +struct UBX_NAV_COV_V0_GROUP0 // clang-format off +{ + uint32_t iTOW; //!< @todo documentation + uint8_t version; //!< @todo documentation + uint8_t posCovValid; //!< @todo documentation + uint8_t velCovValid; //!< @todo documentation + uint8_t reserved[9]; //!< @todo documentation + float posCovNN; //!< @todo documentation + float posCovNE; //!< @todo documentation + float posCovND; //!< @todo documentation + float posCovEE; //!< @todo documentation + float posCovED; //!< @todo documentation + float posCovDD; //!< @todo documentation + float velCovNN; //!< @todo documentation + float velCovNE; //!< @todo documentation + float velCovND; //!< @todo documentation + float velCovEE; //!< @todo documentation + float velCovED; //!< @todo documentation + float velCovDD; //!< @todo documentation +}; +// clang-format on + +static_assert(sizeof(UBX_NAV_COV_V0_GROUP0) == 64, ""); + +// clang-format off +static constexpr uint8_t UBX_NAV_COV_VERSION_GET(const uint8_t* msg) { return msg[UBX_HEAD_SIZE + sizeof(uint32_t)]; } //!< @todo documentation +static constexpr uint8_t UBX_NAV_COV_V0_VERSION = 0x00; //!< @todo documentation +static constexpr std::size_t UBX_NAV_COV_V0_SIZE = sizeof(UBX_NAV_COV_V0_GROUP0) + UBX_FRAME_SIZE; //!< @todo documentation +static constexpr double UBX_NAV_COV_V0_ITOW_SCALE = 1e-3; //!< @todo documentation +// clang-format on + +///@} +// --------------------------------------------------------------------------------------------------------------------- +/** + * @name UBX-NAV-DOP message + * @{ + */ + +//! UBX-NAV-DOP payload +struct UBX_PACKED UBX_NAV_DOP_V0_GROUP0 +{ // clang-format off + uint32_t iTOW; //!< @todo documentation + uint16_t gDOP; //!< @todo documentation + uint16_t pDOP; //!< @todo documentation + uint16_t tDOP; //!< @todo documentation + uint16_t vDOP; //!< @todo documentation + uint16_t hDOP; //!< @todo documentation + uint16_t nDOP; //!< @todo documentation + uint16_t eDOP; //!< @todo documentation +}; // clang-format on + +static_assert(sizeof(UBX_NAV_DOP_V0_GROUP0) == 18, ""); + +// clang-format off +static constexpr std::size_t UBX_NAV_DOP_V0_SIZE = sizeof(UBX_NAV_DOP_V0_GROUP0) + UBX_FRAME_SIZE; //!< @todo documentation +static constexpr double UBX_NAV_DOP_V0_XDOP_SCALE = 1e-2; //!< @todo documentation +// clang-format on + +///@} +// --------------------------------------------------------------------------------------------------------------------- +/** + * @name UBX-NAV-EELL message + * @{ + */ + +//! UBX-NAV-EELL (version 0, output) payload head +struct UBX_NAV_EELL_V0_GROUP0 // clang-format off +{ + uint32_t iTOW; //!< @todo documentation + uint8_t version; //!< @todo documentation + uint8_t reserved; //!< @todo documentation + uint16_t errEllipseOrient; //!< @todo documentation + uint32_t errEllipseMajor; //!< @todo documentation + uint32_t errEllipseMinor; //!< @todo documentation +}; // clang-format on + +static_assert(sizeof(UBX_NAV_EELL_V0_GROUP0) == 16, ""); + +// clang-format off +static constexpr uint8_t UBX_NAV_EELL_VERSION_GET(const uint8_t* msg) { return msg[UBX_HEAD_SIZE]; } //!< @todo documentation +static constexpr uint8_t UBX_NAV_EELL_V0_VERSION = 0x00; //!< @todo documentation +static constexpr std::size_t UBX_NAV_EELL_V0_SIZE = sizeof(UBX_NAV_EELL_V0_GROUP0) + UBX_FRAME_SIZE; //!< @todo documentation +static constexpr double UBX_NAV_EELL_V0_ITOW_SCALE = 1e-3; //!< @todo documentation +static constexpr double UBX_NAV_EELL_V0_ELLIPSEORIENT_SCALE = 1e-2; //!< @todo documentation +static constexpr double UBX_NAV_EELL_V0_ELLIPSEMAJOR_SCALE = 1e-3; //!< @todo documentation +static constexpr double UBX_NAV_EELL_V0_ELLIPSEMINOR_SCALE = 1e-3; //!< @todo documentation +// clang-format on + +///@} +// --------------------------------------------------------------------------------------------------------------------- +/** + * @name UBX-NAV-EOE message + * @{ + */ + +//! UBX-NAV-EOE (version 0, output) payload +struct UBX_NAV_EOE_V0_GROUP0 +{ // clang-format off + uint32_t iTOW; //!< @todo documentation +}; // clang-format on + +static_assert(sizeof(UBX_NAV_EOE_V0_GROUP0) == 4, ""); + +// clang-format off +static constexpr std::size_t UBX_NAV_EOE_V0_SIZE = sizeof(UBX_NAV_EOE_V0_GROUP0) + UBX_FRAME_SIZE; //!< @todo documentation +static constexpr double UBX_NAV_EOE_V0_ITOW_SCALE = 1e-3; //!< @todo documentation +// clang-format on + +///@} +// --------------------------------------------------------------------------------------------------------------------- +/** + * @name UBX-NAV-HPPOSECEF message + * @{ + */ + +//! UBX-NAV-HPPOSECEF (version 0, output) payload +struct UBX_NAV_HPPOSECEF_V0_GROUP0 +{ // clang-format off + uint8_t version; //!< @todo documentation + uint8_t reserved[3]; //!< @todo documentation + uint32_t iTOW; //!< @todo documentation + int32_t ecefX; //!< @todo documentation + int32_t ecefY; //!< @todo documentation + int32_t ecefZ; //!< @todo documentation + int8_t ecefXHp; //!< @todo documentation + int8_t ecefYHp; //!< @todo documentation + int8_t ecefZHp; //!< @todo documentation + uint8_t flags; //!< @todo documentation + uint32_t pAcc; //!< @todo documentation +}; // clang-format on + +static_assert(sizeof(UBX_NAV_HPPOSECEF_V0_GROUP0) == 28, ""); + +// clang-format off +static constexpr uint8_t UBX_NAV_HPPOSECEF_VERSION_GET(const uint8_t* msg) { return msg[UBX_HEAD_SIZE]; } //!< @todo documentation +static constexpr uint8_t UBX_NAV_HPPOSECEF_V0_VERSION = 0x00; //!< @todo documentation +static constexpr std::size_t UBX_NAV_HPPOSECEF_V0_SIZE = sizeof(UBX_NAV_HPPOSECEF_V0_GROUP0) + UBX_FRAME_SIZE; //!< @todo documentation +static constexpr double UBX_NAV_HPPOSECEF_V0_ITOW_SCALE = 1e-3; //!< @todo documentation +static constexpr double UBX_NAV_HPPOSECEF_V0_ECEF_XYZ_SCALE = 1e-2; //!< @todo documentation +static constexpr double UBX_NAV_HPPOSECEF_V0_ECEF_XYZ_HP_SCALE = 1e-4; //!< @todo documentation +static constexpr double UBX_NAV_HPPOSECEF_V0_PACC_SCALE = 1e-4; //!< @todo documentation +static constexpr bool UBX_NAV_HPPOSECEF_V0_FLAGS_INVALIDECEF(const uint8_t flags) { return (flags & 0x01) == 0x01; } //!< @todo documentation +// clang-format on + +///@} +// --------------------------------------------------------------------------------------------------------------------- +/** + * @name UBX-NAV-HPPOSLLH message + * @{ + */ + +//! UBX-NAV-HPPOSLLH (version 0) payload +struct UBX_NAV_HPPOSLLH_V0_GROUP0 // clang-format off +{ + uint8_t version; //!< @todo documentation + uint8_t reserved[2]; //!< @todo documentation + uint8_t flags; //!< @todo documentation + uint32_t iTOW; //!< @todo documentation + int32_t lon; //!< @todo documentation + int32_t lat; //!< @todo documentation + int32_t height; //!< @todo documentation + int32_t hMSL; //!< @todo documentation + int8_t lonHp; //!< @todo documentation + int8_t latHp; //!< @todo documentation + int8_t heightHp; //!< @todo documentation + int8_t hMSLHp; //!< @todo documentation + uint32_t hAcc; //!< @todo documentation + uint32_t vAcc; //!< @todo documentation +}; // clang-format on + +static_assert(sizeof(UBX_NAV_HPPOSLLH_V0_GROUP0) == 36, ""); + +// clang-format off +static constexpr uint8_t UBX_NAV_HPPOSLLH_VERSION_GET(const uint8_t* msg) { return msg[UBX_HEAD_SIZE]; } //!< @todo documentation +static constexpr uint8_t UBX_NAV_HPPOSLLH_V0_VERSION = 0x00; //!< @todo documentation +static constexpr std::size_t UBX_NAV_HPPOSLLH_V0_SIZE = sizeof(UBX_NAV_HPPOSLLH_V0_GROUP0) + UBX_FRAME_SIZE; //!< @todo documentation +static constexpr uint8_t UBX_NAV_HPPOSLLH_V0_FLAGS_INVALIDLLH = 0x01; //!< @todo documentation +static constexpr double UBX_NAV_HPPOSLLH_V0_ITOW_SCALE = 1e-3; //!< @todo documentation +static constexpr double UBX_NAV_HPPOSLLH_V0_LL_SCALE = 1e-7; //!< @todo documentation +static constexpr double UBX_NAV_HPPOSLLH_V0_H_SCALE = 1e-3; //!< @todo documentation +static constexpr double UBX_NAV_HPPOSLLH_V0_LL_HP_SCALE = 1e-9; //!< @todo documentation +static constexpr double UBX_NAV_HPPOSLLH_V0_H_HP_SCALE = 1e-4; //!< @todo documentation +static constexpr double UBX_NAV_HPPOSLLH_V0_ACC_SCALE = 1e-4; //!< @todo documentation +// clang-format on + +///@} +// --------------------------------------------------------------------------------------------------------------------- +/** + * @name UBX-NAV-POSECEF message + * @{ + */ + +//! UBX-NAV-POSECEF (version 0, output) payload +struct UBX_NAV_POSECEF_V0_GROUP0 // clang-format off +{ + uint32_t iTOW; //!< @todo documentation + int32_t ecefX; //!< @todo documentation + int32_t ecefY; //!< @todo documentation + int32_t ecefZ; //!< @todo documentation + uint32_t pAcc; //!< @todo documentation +}; // clang-format on + +static_assert(sizeof(UBX_NAV_POSECEF_V0_GROUP0) == 20, ""); + +// clang-format off +static constexpr std::size_t UBX_NAV_POSECEF_V0_SIZE = sizeof(UBX_NAV_POSECEF_V0_GROUP0) + UBX_FRAME_SIZE; //!< @todo documentation +static constexpr double UBX_NAV_POSECEF_V0_ECEF_XYZ_SCALE = 1e-2; //!< @todo documentation +static constexpr double UBX_NAV_POSECEF_V0_PACC_SCALE = 1e-2; //!< @todo documentation +// clang-format on + +///@} +// --------------------------------------------------------------------------------------------------------------------- +/** + * @name UBX-NAV-PVT message + * @{ + */ + +//! UBX-NAV-PVT (version 1, output) payload +struct UBX_NAV_PVT_V1_GROUP0 // clang-format off + { + uint32_t iTOW; //!< @todo documentation + uint16_t year; //!< @todo documentation + uint8_t month; //!< @todo documentation + uint8_t day; //!< @todo documentation + uint8_t hour; //!< @todo documentation + uint8_t min; //!< @todo documentation + uint8_t sec; //!< @todo documentation + uint8_t valid; //!< @todo documentation + uint32_t tAcc; //!< @todo documentation + int32_t nano; //!< @todo documentation + uint8_t fixType; //!< @todo documentation + uint8_t flags; //!< @todo documentation + uint8_t flags2; //!< @todo documentation + uint8_t numSV; //!< @todo documentation + int32_t lon; //!< @todo documentation + int32_t lat; //!< @todo documentation + int32_t height; //!< @todo documentation + int32_t hMSL; //!< @todo documentation + uint32_t hAcc; //!< @todo documentation + uint32_t vAcc; //!< @todo documentation + int32_t velN; //!< @todo documentation + int32_t velE; //!< @todo documentation + int32_t velD; //!< @todo documentation + int32_t gSpeed; //!< @todo documentation + int32_t headMot; //!< @todo documentation + uint32_t sAcc; //!< @todo documentation + uint32_t headAcc; //!< @todo documentation + uint16_t pDOP; //!< @todo documentation + uint8_t flags3; //!< @todo documentation + uint8_t reserved[5]; //!< @todo documentation + int32_t headVeh; //!< @todo documentation + int16_t magDec; //!< @todo documentation + uint16_t magAcc; //!< @todo documentation +}; // clang-format on + +static_assert(sizeof(UBX_NAV_PVT_V1_GROUP0) == 92, ""); + +// clang-format off +static constexpr std::size_t UBX_NAV_PVT_V1_SIZE = sizeof(UBX_NAV_PVT_V1_GROUP0) + UBX_FRAME_SIZE; //!< @todo documentation +static constexpr double UBX_NAV_PVT_V1_ITOW_SCALE = 1e-3; //!< @todo documentation +static constexpr bool UBX_NAV_PVT_V1_VALID_VALIDDATE(const uint8_t valid) { return (valid & 0x01) == 0x01; } //!< @todo documentation +static constexpr bool UBX_NAV_PVT_V1_VALID_VALIDTIME(const uint8_t valid) { return (valid & 0x02) == 0x02; } //!< @todo documentation +static constexpr bool UBX_NAV_PVT_V1_VALID_FULLYRESOLVED(const uint8_t valid) { return (valid & 0x04) == 0x04; } //!< @todo documentation +static constexpr bool UBX_NAV_PVT_V1_VALID_VALIDMAG(const uint8_t valid) { return (valid & 0x08) == 0x08; } //!< @todo documentation +static constexpr uint8_t UBX_NAV_PVT_V1_FIXTYPE_NOFIX = 0; //!< @todo documentation +static constexpr uint8_t UBX_NAV_PVT_V1_FIXTYPE_DRONLY = 1; //!< @todo documentation +static constexpr uint8_t UBX_NAV_PVT_V1_FIXTYPE_2D = 2; //!< @todo documentation +static constexpr uint8_t UBX_NAV_PVT_V1_FIXTYPE_3D = 3; //!< @todo documentation +static constexpr uint8_t UBX_NAV_PVT_V1_FIXTYPE_3D_DR = 4; //!< @todo documentation +static constexpr uint8_t UBX_NAV_PVT_V1_FIXTYPE_TIME = 5; //!< @todo documentation +static constexpr bool UBX_NAV_PVT_V1_FLAGS_GNSSFIXOK(const uint8_t flags) { return (flags & 0x01) == 0x01; } //!< @todo documentation +static constexpr bool UBX_NAV_PVT_V1_FLAGS_DIFFSOLN(const uint8_t flags) { return (flags & 0x02) == 0x02; } //!< @todo documentation +static constexpr uint8_t UBX_NAV_PVT_V1_FLAGS_CARRSOLN_GET(const uint8_t flags) { return (flags >> 6) & 0x03; } //!< @todo documentation +static constexpr uint8_t UBX_NAV_PVT_V1_FLAGS_CARRSOLN_NO = 0; //!< @todo documentation +static constexpr uint8_t UBX_NAV_PVT_V1_FLAGS_CARRSOLN_FLOAT = 1; //!< @todo documentation +static constexpr uint8_t UBX_NAV_PVT_V1_FLAGS_CARRSOLN_FIXED = 2; //!< @todo documentation +static constexpr bool UBX_NAV_PVT_V1_FLAGS2_CONFAVAIL(const uint8_t flags2) { return (flags2 & 0x20) == 0x20; } //!< @todo documentation +static constexpr bool UBX_NAV_PVT_V1_FLAGS2_CONFDATE(const uint8_t flags2) { return (flags2 & 0x40) == 0x40; } //!< @todo documentation +static constexpr bool UBX_NAV_PVT_V1_FLAGS2_CONFTIME(const uint8_t flags2) { return (flags2 & 0x80) == 0x80; } //!< @todo documentation +static constexpr bool UBX_NAV_PVT_V1_FLAGS3_INVALIDLLH(const uint8_t flags3) { return (flags3 & 0x01) == 0x01; } //!< @todo documentation +static constexpr double UBX_NAV_PVT_V1_LAT_SCALE = 1e-7; //!< @todo documentation +static constexpr double UBX_NAV_PVT_V1_LON_SCALE = 1e-7; //!< @todo documentation +static constexpr double UBX_NAV_PVT_V1_HEIGHT_SCALE = 1e-3; //!< @todo documentation +static constexpr double UBX_NAV_PVT_V1_HACC_SCALE = 1e-3; //!< @todo documentation +static constexpr double UBX_NAV_PVT_V1_VACC_SCALE = 1e-3; //!< @todo documentation +static constexpr double UBX_NAV_PVT_V1_VELNED_SCALE = 1e-3; //!< @todo documentation +static constexpr double UBX_NAV_PVT_V1_GSPEED_SCALE = 1e-3; //!< @todo documentation +static constexpr double UBX_NAV_PVT_V1_HEADMOT_SCALE = 1e-5; //!< @todo documentation +static constexpr double UBX_NAV_PVT_V1_SACC_SCALE = 1e-3; //!< @todo documentation +static constexpr double UBX_NAV_PVT_V1_HEADACC_SCALE = 1e-5; //!< @todo documentation +static constexpr double UBX_NAV_PVT_V1_PDOP_SCALE = 1e-2; //!< @todo documentation +static constexpr double UBX_NAV_PVT_V1_TACC_SCALE = 1e-9; //!< @todo documentation +static constexpr double UBX_NAV_PVT_V1_NANO_SCALE = 1e-9; //!< @todo documentation +// clang-format on + +///@} +// --------------------------------------------------------------------------------------------------------------------- +/** + * @name UBX-NAV-RELPOSNED message + * @{ + */ + +//! UBX-NAV-RELPOSNED (version 1, output) payload +struct UBX_NAV_RELPOSNED_V1_GROUP0 // clang-format off +{ + uint8_t version; //!< @todo documentation + uint8_t reserved0; //!< @todo documentation + uint16_t refStationId; //!< @todo documentation + uint32_t iTOW; //!< @todo documentation + int32_t relPosN; //!< @todo documentation + int32_t relPosE; //!< @todo documentation + int32_t relPosD; //!< @todo documentation + int32_t relPosLength; //!< @todo documentation + int32_t relPosHeading; //!< @todo documentation + uint8_t reserved1[4]; //!< @todo documentation + int8_t relPosHPN; //!< @todo documentation + int8_t relPosHPE; //!< @todo documentation + int8_t relPosHPD; //!< @todo documentation + int8_t relPosHPLength; //!< @todo documentation + uint32_t accN; //!< @todo documentation + uint32_t accE; //!< @todo documentation + uint32_t accD; //!< @todo documentation + uint32_t accLength; //!< @todo documentation + uint32_t accHeading; //!< @todo documentation + uint8_t reserved2[4]; //!< @todo documentation + uint32_t flags; //!< @todo documentation +}; // clang-format on + +static_assert(sizeof(UBX_NAV_RELPOSNED_V1_GROUP0) == 64, ""); + +// clang-format off +static constexpr uint8_t UBX_NAV_RELPOSNED_VERSION_GET(const uint8_t* msg) { return msg[UBX_HEAD_SIZE]; } //!< @todo documentation +static constexpr uint8_t UBX_NAV_RELPOSNED_V1_VERSION = 0x01; //!< @todo documentation +static constexpr std::size_t UBX_NAV_RELPOSNED_V1_SIZE = sizeof(UBX_NAV_RELPOSNED_V1_GROUP0) + UBX_FRAME_SIZE; //!< @todo documentation +static constexpr double UBX_NAV_RELPOSNED_V1_ITOW_SCALE = 1e-3; //!< @todo documentation +static constexpr double UBX_NAV_RELPOSNED_V1_RELPOSN_E_D_SCALE = 1e-2; //!< @todo documentation +static constexpr double UBX_NAV_RELPOSNED_V1_RELPOSLENGTH_SCALE = 1e-2; //!< @todo documentation +static constexpr double UBX_NAV_RELPOSNED_V1_RELPOSHEADING_SCALE = 1e-5; //!< @todo documentation +static constexpr double UBX_NAV_RELPOSNED_V1_RELPOSHPN_E_D_SCALE = 1e-4; //!< @todo documentation +static constexpr double UBX_NAV_RELPOSNED_V1_RELPOSHPLENGTH_SCALE = 1e-4; //!< @todo documentation +static constexpr double UBX_NAV_RELPOSNED_V1_ACCN_E_D_SCALE = 1e-4; //!< @todo documentation +static constexpr double UBX_NAV_RELPOSNED_V1_ACCLENGTH_SCALE = 1e-4; //!< @todo documentation +static constexpr double UBX_NAV_RELPOSNED_V1_ACCHEADING_SCALE = 1e-5; //!< @todo documentation +static constexpr bool UBX_NAV_RELPOSNED_V1_FLAGS_GNSSFIXOK(const uint32_t flags) { return (flags & 0x00000001) == 0x00000001; } //!< @todo documentation +static constexpr bool UBX_NAV_RELPOSNED_V1_FLAGS_DIFFSOLN(const uint32_t flags) { return (flags & 0x00000002) == 0x00000002; } //!< @todo documentation +static constexpr bool UBX_NAV_RELPOSNED_V1_FLAGS_RELPOSVALID(const uint32_t flags) { return (flags & 0x00000004) == 0x00000004; } //!< @todo documentation +static constexpr uint8_t UBX_NAV_RELPOSNED_V1_FLAGS_CARRSOLN_GET(const uint32_t flags) { return (flags >> 3) & 0x03; } //!< @todo documentation +static constexpr uint8_t UBX_NAV_RELPOSNED_V1_FLAGS_CARRSOLN_NO = 0; //!< @todo documentation +static constexpr uint8_t UBX_NAV_RELPOSNED_V1_FLAGS_CARRSOLN_FLOAT = 1; //!< @todo documentation +static constexpr uint8_t UBX_NAV_RELPOSNED_V1_FLAGS_CARRSOLN_FIXED = 2; //!< @todo documentation +static constexpr bool UBX_NAV_RELPOSNED_V1_FLAGS_ISMOVING(const uint32_t flags) { return (flags & 0x00000020) == 0x00000020; } //!< @todo documentation +static constexpr bool UBX_NAV_RELPOSNED_V1_FLAGS_REFPOSMISS(const uint32_t flags) { return (flags & 0x00000040) == 0x00000040; } //!< @todo documentation +static constexpr bool UBX_NAV_RELPOSNED_V1_FLAGS_REFOBSMISS(const uint32_t flags) { return (flags & 0x00000080) == 0x00000080; } //!< @todo documentation +static constexpr bool UBX_NAV_RELPOSNED_V1_FLAGS_RELPOSHEADINGVALID(const uint32_t flags) { return (flags & 0x00000100) == 0x00000100; } //!< @todo documentation +static constexpr bool UBX_NAV_RELPOSNED_V1_FLAGS_RELPOSNORMALIZED(const uint32_t flags) { return (flags & 0x00000200) == 0x00000200; } //!< @todo documentation +// clang-format on + +///@} +// --------------------------------------------------------------------------------------------------------------------- +/** + * @name UBX-NAV-SAT message + * @{ + */ + +//! UBX-NAV-SAT (version 1, output) payload head +struct UBX_NAV_SAT_V1_GROUP0 // clang-format off +{ + uint32_t iTOW; //!< @todo documentation + uint8_t version; //!< @todo documentation + uint8_t numSvs; //!< @todo documentation + uint8_t reserved[2]; //!< @todo documentation +}; // clang-format on + +static_assert(sizeof(UBX_NAV_SAT_V1_GROUP0) == 8, ""); + +//! UBX-NAV-SAT (version 1, output) payload repeated group +struct UBX_NAV_SAT_V1_GROUP1 // clang-format off +{ + uint8_t gnssId; //!< @todo documentation + uint8_t svId; //!< @todo documentation + uint8_t cno; //!< @todo documentation + int8_t elev; //!< @todo documentation + int16_t azim; //!< @todo documentation + int16_t prRes; //!< @todo documentation + uint32_t flags; //!< @todo documentation +}; // clang-format on + +static_assert(sizeof(UBX_NAV_SAT_V1_GROUP1) == 12, ""); + +// clang-format off +static constexpr uint8_t UBX_NAV_SAT_VERSION_GET(const uint8_t* msg) { return msg[UBX_HEAD_SIZE + sizeof(uint32_t)]; } //!< @todo documentation +static constexpr uint8_t UBX_NAV_SAT_V1_VERSION = 0x01; //!< @todo documentation +static constexpr std::size_t UBX_NAV_SAT_V1_MIN_SIZE = sizeof(UBX_NAV_SAT_V1_GROUP0) + UBX_FRAME_SIZE; //!< @todo documentation +static constexpr double UBX_NAV_SAT_V1_ITOW_SCALE = 1e-3; //!< @todo documentation +// Note: only those flags relevant for a SV are defined below. All other info should be taken from UBX-NAV-SIG. //!< @todo documentation +static constexpr uint8_t UBX_NAV_SAT_V1_FLAGS_ORBITSOURCE_GET(const uint32_t flags) { return (flags >> 8) & 0x00000007; } //!< @todo documentation +static constexpr uint8_t UBX_NAV_SAT_V1_FLAGS_ORBITSOURCE_NONE = 0; //!< @todo documentation +static constexpr uint8_t UBX_NAV_SAT_V1_FLAGS_ORBITSOURCE_EPH = 1; //!< @todo documentation +static constexpr uint8_t UBX_NAV_SAT_V1_FLAGS_ORBITSOURCE_ALM = 2; //!< @todo documentation +static constexpr uint8_t UBX_NAV_SAT_V1_FLAGS_ORBITSOURCE_ANO = 3; //!< @todo documentation +static constexpr uint8_t UBX_NAV_SAT_V1_FLAGS_ORBITSOURCE_ANA = 4; //!< @todo documentation +static constexpr uint8_t UBX_NAV_SAT_V1_FLAGS_ORBITSOURCE_OTHER1 = 5; //!< @todo documentation +static constexpr uint8_t UBX_NAV_SAT_V1_FLAGS_ORBITSOURCE_OTHER2 = 6; //!< @todo documentation +static constexpr uint8_t UBX_NAV_SAT_V1_FLAGS_ORBITSOURCE_OTHER3 = 7; //!< @todo documentation +static constexpr bool UBX_NAV_SAT_V1_FLAGS_EPHAVAIL(const uint32_t flags) { return (flags & 0x00000800) == 0x00000800; } //!< @todo documentation +static constexpr bool UBX_NAV_SAT_V1_FLAGS_ALMAVAIL(const uint32_t flags) { return (flags & 0x00001000) == 0x00001000; } //!< @todo documentation +static constexpr bool UBX_NAV_SAT_V1_FLAGS_ANOAVAIL(const uint32_t flags) { return (flags & 0x00002000) == 0x00002000; } //!< @todo documentation +static constexpr bool UBX_NAV_SAT_V1_FLAGS_AOPAVAIL(const uint32_t flags) { return (flags & 0x00004000) == 0x00004000; } //!< @todo documentation +// clang-format on + +///@} +// --------------------------------------------------------------------------------------------------------------------- +/** + * @name UBX-NAV-SIG message + * @{ + */ + +//! UBX-NAV-SIG (version 0, output) payload head +struct UBX_NAV_SIG_V0_GROUP0 // clang-format off +{ + uint32_t iTOW; //!< @todo documentation + uint8_t version; //!< @todo documentation + uint8_t numSigs; //!< @todo documentation + uint8_t reserved[2]; //!< @todo documentation +}; // clang-format on + +static_assert(sizeof(UBX_NAV_SIG_V0_GROUP0) == 8, ""); + +//! UBX-NAV-SIG (version 0, output) payload repeated group +struct UBX_NAV_SIG_V0_GROUP1 // clang-format off +{ + uint8_t gnssId; //!< @todo documentation + uint8_t svId; //!< @todo documentation + uint8_t sigId; //!< @todo documentation + uint8_t freqId; //!< @todo documentation + int16_t prRes; //!< @todo documentation + uint8_t cno; //!< @todo documentation + uint8_t qualityInd; //!< @todo documentation + uint8_t corrSource; //!< @todo documentation + uint8_t ionoModel; //!< @todo documentation + uint16_t sigFlags; //!< @todo documentation + uint8_t reserved[4]; //!< @todo documentation +}; // clang-format on + +static_assert(sizeof(UBX_NAV_SIG_V0_GROUP1) == 16, ""); + +// clang-format off +static constexpr uint8_t UBX_NAV_SIG_VERSION_GET(const uint8_t* msg) { return msg[UBX_HEAD_SIZE + sizeof(uint32_t)]; } //!< @todo documentation +static constexpr uint8_t UBX_NAV_SIG_V0_VERSION = 0x00; //!< @todo documentation +static constexpr std::size_t UBX_NAV_SIG_V0_MIN_SIZE = sizeof(UBX_NAV_SIG_V0_GROUP0) + UBX_FRAME_SIZE; //!< @todo documentation +static constexpr double UBX_NAV_SIG_V0_ITOW_SCALE = 1e-3; //!< @todo documentation +static constexpr std::size_t UBX_NAV_SIG_V0_FREQID_OFFS = 7; //!< @todo documentation +static constexpr uint8_t UBX_NAV_SIG_V0_QUALITYIND_NOSIG = 0; //!< @todo documentation +static constexpr uint8_t UBX_NAV_SIG_V0_QUALITYIND_SEARCH = 1; //!< @todo documentation +static constexpr uint8_t UBX_NAV_SIG_V0_QUALITYIND_ACQUIRED = 2; //!< @todo documentation +static constexpr uint8_t UBX_NAV_SIG_V0_QUALITYIND_UNUSED = 3; //!< @todo documentation +static constexpr uint8_t UBX_NAV_SIG_V0_QUALITYIND_CODELOCK = 4; //!< @todo documentation +static constexpr uint8_t UBX_NAV_SIG_V0_QUALITYIND_CARRLOCK1 = 5; //!< @todo documentation +static constexpr uint8_t UBX_NAV_SIG_V0_QUALITYIND_CARRLOCK2 = 6; //!< @todo documentation +static constexpr uint8_t UBX_NAV_SIG_V0_QUALITYIND_CARRLOCK3 = 7; //!< @todo documentation +static constexpr uint8_t UBX_NAV_SIG_V0_IONOMODEL_NONE = 0; //!< @todo documentation +static constexpr uint8_t UBX_NAV_SIG_V0_IONOMODEL_KLOB_GPS = 1; //!< @todo documentation +static constexpr uint8_t UBX_NAV_SIG_V0_IONOMODEL_SBAS = 2; //!< @todo documentation +static constexpr uint8_t UBX_NAV_SIG_V0_IONOMODEL_KLOB_BDS = 3; //!< @todo documentation +static constexpr uint8_t UBX_NAV_SIG_V0_IONOMODEL_DUALFREQ = 8; //!< @todo documentation +static constexpr uint8_t UBX_NAV_SIG_V0_SIGFLAGS_HEALTH_GET(const uint16_t sigFlags) { return sigFlags & 0x03; } //!< @todo documentation +static constexpr uint8_t UBX_NAV_SIG_V0_SIGFLAGS_HEALTH_UNKNO = 0; //!< @todo documentation +static constexpr uint8_t UBX_NAV_SIG_V0_SIGFLAGS_HEALTH_HEALTHY = 1; //!< @todo documentation +static constexpr uint8_t UBX_NAV_SIG_V0_SIGFLAGS_HEALTH_UNHEALTHY = 2; //!< @todo documentation +static constexpr bool UBX_NAV_SIG_V0_SIGFLAGS_PR_SMOOTHED(const uint16_t sigFlags) { return (sigFlags & 0x0004) == 0x0004; } //!< @todo documentation +static constexpr bool UBX_NAV_SIG_V0_SIGFLAGS_PR_USED(const uint16_t sigFlags) { return (sigFlags & 0x0008) == 0x0008; } //!< @todo documentation +static constexpr bool UBX_NAV_SIG_V0_SIGFLAGS_CR_USED(const uint16_t sigFlags) { return (sigFlags & 0x0010) == 0x0010; } //!< @todo documentation +static constexpr bool UBX_NAV_SIG_V0_SIGFLAGS_DO_USED(const uint16_t sigFlags) { return (sigFlags & 0x0020) == 0x0020; } //!< @todo documentation +static constexpr bool UBX_NAV_SIG_V0_SIGFLAGS_PR_CORR_USED(const uint16_t sigFlags) { return (sigFlags & 0x0040) == 0x0040; } //!< @todo documentation +static constexpr bool UBX_NAV_SIG_V0_SIGFLAGS_CR_CORR_USED(const uint16_t sigFlags) { return (sigFlags & 0x0080) == 0x0080; } //!< @todo documentation +static constexpr bool UBX_NAV_SIG_V0_SIGFLAGS_DO_CORR_USED(const uint16_t sigFlags) { return (sigFlags & 0x0100) == 0x0100; } //!< @todo documentation +static constexpr uint8_t UBX_NAV_SIG_V0_CORRSOURCE_NONE = 0; //!< @todo documentation +static constexpr uint8_t UBX_NAV_SIG_V0_CORRSOURCE_SBAS = 1; //!< @todo documentation +static constexpr uint8_t UBX_NAV_SIG_V0_CORRSOURCE_BDS = 2; //!< @todo documentation +static constexpr uint8_t UBX_NAV_SIG_V0_CORRSOURCE_RTCM2 = 3; //!< @todo documentation +static constexpr uint8_t UBX_NAV_SIG_V0_CORRSOURCE_RTCM3_OSR = 4; //!< @todo documentation +static constexpr uint8_t UBX_NAV_SIG_V0_CORRSOURCE_RTCM3_SSR = 5; //!< @todo documentation +static constexpr uint8_t UBX_NAV_SIG_V0_CORRSOURCE_QZSS_SLAS = 6; //!< @todo documentation +static constexpr uint8_t UBX_NAV_SIG_V0_CORRSOURCE_SPARTN = 7; //!< @todo documentation +static constexpr double UBX_NAV_SIG_V0_PRRES_SCALE = 1e-1; //!< @todo documentation +// clang-format on + +///@} +// --------------------------------------------------------------------------------------------------------------------- +/** + * @name UBX-NAV-STATUS message + * @{ + */ + +//! UBX-NAV-STATUS payload +struct UBX_NAV_STATUS_V0_GROUP0 // clang-format off +{ + uint32_t iTow; //!< @todo documentation + uint8_t gpsFix; //!< @todo documentation + uint8_t flags; //!< @todo documentation + uint8_t fixStat; //!< @todo documentation + uint8_t flags2; //!< @todo documentation + uint32_t ttff; //!< @todo documentation + uint32_t msss; //!< @todo documentation +}; // clang-format on + +static_assert(sizeof(UBX_NAV_STATUS_V0_GROUP0) == 16, ""); + +// clang-format off +static constexpr std::size_t UBX_NAV_STATUS_V0_SIZE = sizeof(UBX_NAV_STATUS_V0_GROUP0) + UBX_FRAME_SIZE; //!< @todo documentation +static constexpr double UBX_NAV_STATUS_V0_ITOW_SCALE = 1e-3; //!< @todo documentation +static constexpr uint8_t UBX_NAV_STATUS_V0_FIXTYPE_NOFIX = 0; //!< @todo documentation +static constexpr uint8_t UBX_NAV_STATUS_V0_FIXTYPE_DRONLY = 1; //!< @todo documentation +static constexpr uint8_t UBX_NAV_STATUS_V0_FIXTYPE_2D = 2; //!< @todo documentation +static constexpr uint8_t UBX_NAV_STATUS_V0_FIXTYPE_3D = 3; //!< @todo documentation +static constexpr uint8_t UBX_NAV_STATUS_V0_FIXTYPE_3D_DR = 4; //!< @todo documentation +static constexpr uint8_t UBX_NAV_STATUS_V0_FIXTYPE_TIME = 5; //!< @todo documentation +static constexpr bool UBX_NAV_STATUS_V0_FLAGS_GPSFIXOK(const uint8_t flags) { return (flags & 0x01) == 0x01; } //!< @todo documentation +static constexpr bool UBX_NAV_STATUS_V0_FLAGS_DIFFSOLN(const uint8_t flags) { return (flags & 0x02) == 0x02; } //!< @todo documentation +static constexpr bool UBX_NAV_STATUS_V0_FLAGS_WKNSET(const uint8_t flags) { return (flags & 0x04) == 0x04; } //!< @todo documentation +static constexpr bool UBX_NAV_STATUS_V0_FLAGS_TOWSET(const uint8_t flags) { return (flags & 0x08) == 0x08; } //!< @todo documentation +static constexpr uint8_t UBX_NAV_STATUS_V0_FIXSTAT_DIFFCORR = 0x01; //!< @todo documentation +static constexpr uint8_t UBX_NAV_STATUS_V0_FIXSTAT_CARRSOLNVALID = 0x02; //!< @todo documentation +static constexpr uint8_t UBX_NAV_STATUS_V0_FLAGS2_CARRSOLN_GET(const uint8_t flags2) { return (flags2 >> 6) & 0x03; } //!< @todo documentation +static constexpr uint8_t UBX_NAV_STATUS_V0_FLAGS2_CARRSOLN_NO = 0; //!< @todo documentation +static constexpr uint8_t UBX_NAV_STATUS_V0_FLAGS2_CARRSOLN_FLOAT = 1; //!< @todo documentation +static constexpr uint8_t UBX_NAV_STATUS_V0_FLAGS2_CARRSOLN_FIXED = 2; //!< @todo documentation +static constexpr double UBX_NAV_STATUS_V0_TTFF_SCALE = 1e-3; //!< @todo documentation +static constexpr double UBX_NAV_STATUS_V0_MSSS_SCALE = 1e-3; //!< @todo documentation +// clang-format on + +///@} +// --------------------------------------------------------------------------------------------------------------------- +/** + * @name UBX-NAV-TIMEGPS message + * @{ + */ + +//! UBX-NAV-TIMEGPS payload +struct UBX_NAV_TIMEGPS_V0_GROUP0 // clang-format off +{ + uint32_t iTow; //!< @todo documentation + int32_t fTOW; //!< @todo documentation + int16_t week; //!< @todo documentation + int8_t leapS; //!< @todo documentation + uint8_t valid; //!< @todo documentation + uint32_t tAcc; //!< @todo documentation +}; // clang-format on + +static_assert(sizeof(UBX_NAV_TIMEGPS_V0_GROUP0) == 16, ""); + +// clang-format off +static constexpr std::size_t UBX_NAV_TIMEGPS_V0_SIZE = sizeof(UBX_NAV_TIMEGPS_V0_GROUP0) + UBX_FRAME_SIZE; //!< @todo documentation +static constexpr double UBX_NAV_TIMEGPS_V0_ITOW_SCALE = 1e-3; //!< @todo documentation +static constexpr double UBX_NAV_TIMEGPS_V0_FTOW_SCALE = 1e-9; //!< @todo documentation +static constexpr double UBX_NAV_TIMEGPS_V0_TACC_SCALE = 1e-9; //!< @todo documentation +static constexpr bool UBX_NAV_TIMEGPS_V0_VALID_TOWVALID(const uint8_t valid) { return (valid & 0x01) == 0x01; } //!< @todo documentation +static constexpr bool UBX_NAV_TIMEGPS_V0_VALID_WEEKVALID(const uint8_t valid) { return (valid & 0x02) == 0x02; } //!< @todo documentation +static constexpr bool UBX_NAV_TIMEGPS_V0_VALID_LEAPSVALID(const uint8_t valid) { return (valid & 0x04) == 0x04; } //!< @todo documentation +// clang-format on + +///@} +// --------------------------------------------------------------------------------------------------------------------- +/** + * @name UBX-NAV-TIMEGAL message + * @{ + */ + +//! UBX-NAV-TIMEGAL payload +struct UBX_NAV_TIMEGAL_V0_GROUP0 // clang-format off +{ + uint32_t iTow; //!< @todo documentation + uint32_t galTow; //!< @todo documentation + int32_t fGalTow; //!< @todo documentation + int16_t galWno; //!< @todo documentation + int8_t leapS; //!< @todo documentation + uint8_t valid; //!< @todo documentation + uint32_t tAcc; //!< @todo documentation +}; // clang-format on + +static_assert(sizeof(UBX_NAV_TIMEGAL_V0_GROUP0) == 20, ""); + +// clang-format off +static constexpr std::size_t UBX_NAV_TIMEGAL_V0_SIZE = sizeof(UBX_NAV_TIMEGAL_V0_GROUP0) + UBX_FRAME_SIZE; //!< @todo documentation +static constexpr double UBX_NAV_TIMEGAL_V0_ITOW_SCALE = 1e-3; //!< @todo documentation +static constexpr double UBX_NAV_TIMEGAL_V0_FGALTOW_SCALE = 1e-9; //!< @todo documentation +static constexpr double UBX_NAV_TIMEGAL_V0_TACC_SCALE = 1e-9; //!< @todo documentation +static constexpr bool UBX_NAV_TIMEGAL_V0_VALID_GALTOWVALID(const uint8_t valid) { return (valid & 0x01) == 0x01; } //!< @todo documentation +static constexpr bool UBX_NAV_TIMEGAL_V0_VALID_GALWNOVALID(const uint8_t valid) { return (valid & 0x02) == 0x02; } //!< @todo documentation +static constexpr bool UBX_NAV_TIMEGAL_V0_VALID_LEAPSVALID(const uint8_t valid) { return (valid & 0x04) == 0x04; } //!< @todo documentation +// clang-format on + +///@} +// --------------------------------------------------------------------------------------------------------------------- +/** + * @name UBX-NAV-TIMEBDS message + * @{ + */ + +//! UBX-NAV-TIMEBDS payload +struct UBX_NAV_TIMEBDS_V0_GROUP0 // clang-format off +{ + uint32_t iTow; //!< @todo documentation + uint32_t SOW; //!< @todo documentation + int32_t fSOW; //!< @todo documentation + int16_t week; //!< @todo documentation + int8_t leapS; //!< @todo documentation + uint8_t valid; //!< @todo documentation + uint32_t tAcc; //!< @todo documentation +}; // clang-format on + +static_assert(sizeof(UBX_NAV_TIMEBDS_V0_GROUP0) == 20, ""); + +// clang-format off +static constexpr uint32_t UBX_NAV_TIMEBDS_V0_SIZE = sizeof(UBX_NAV_TIMEBDS_V0_GROUP0) + UBX_FRAME_SIZE; //!< @todo documentation +static constexpr double UBX_NAV_TIMEBDS_V0_ITOW_SCALE = 1e-3; //!< @todo documentation +static constexpr double UBX_NAV_TIMEBDS_V0_FSOW_SCALE = 1e-9; //!< @todo documentation +static constexpr double UBX_NAV_TIMEBDS_V0_TACC_SCALE = 1e-9; //!< @todo documentation +static constexpr bool UBX_NAV_TIMEBDS_V0_VALID_SOWVALID(const uint8_t valid) { return (valid & 0x01) == 0x01; } //!< @todo documentation +static constexpr bool UBX_NAV_TIMEBDS_V0_VALID_WEEKVALID(const uint8_t valid) { return (valid & 0x02) == 0x02; } //!< @todo documentation +static constexpr bool UBX_NAV_TIMEBDS_V0_VALID_LEAPSVALID(const uint8_t valid) { return (valid & 0x04) == 0x04; } //!< @todo documentation +// clang-format on + +///@} +// --------------------------------------------------------------------------------------------------------------------- +/** + * @name UBX-NAV-TIMEGLO message + * @{ + */ + +//! UBX-NAV-TIMEGLO payload +struct UBX_NAV_TIMEGLO_V0_GROUP0 // clang-format off +{ + uint32_t iTow; //!< @todo documentation + uint32_t TOD; //!< @todo documentation + int32_t fTOD; //!< @todo documentation + uint16_t Nt; //!< @todo documentation + uint8_t N4; //!< @todo documentation + uint8_t valid; //!< @todo documentation + uint32_t tAcc; //!< @todo documentation +}; // clang-format on + +static_assert(sizeof(UBX_NAV_TIMEGLO_V0_GROUP0) == 20, ""); + +// clang-format off +static constexpr double UBX_NAV_TIMEGLO_V0_SIZE = sizeof(UBX_NAV_TIMEGLO_V0_GROUP0) + UBX_FRAME_SIZE; //!< @todo documentation +static constexpr double UBX_NAV_TIMEGLO_V0_ITOW_SCALE = 1e-3; //!< @todo documentation +static constexpr double UBX_NAV_TIMEGLO_V0_FTOD_SCALE = 1e-9; //!< @todo documentation +static constexpr double UBX_NAV_TIMEGLO_V0_TACC_SCALE = 1e-9; //!< @todo documentation +static constexpr bool UBX_NAV_TIMEGLO_V0_VALID_TODVALID(const uint8_t valid) { return (valid & 0x01) == 0x01; } //!< @todo documentation +static constexpr bool UBX_NAV_TIMEGLO_V0_VALID_DATEVALID(const uint8_t valid) { return (valid & 0x02) == 0x02; } //!< @todo documentation +// clang-format on + +///@} +// --------------------------------------------------------------------------------------------------------------------- +/** + * @name UBX-NAV-TIMEUTC message + * @{ + */ + +//! UBX-NAV-TIMEUTC payload +struct UBX_NAV_TIMEUTC_V0_GROUP0 // clang-format off + { + uint32_t iTow; //!< @todo documentation + uint32_t tAcc; //!< @todo documentation + int32_t nano; //!< @todo documentation + uint16_t year; //!< @todo documentation + uint8_t month; //!< @todo documentation + uint8_t day; //!< @todo documentation + uint8_t hour; //!< @todo documentation + uint8_t min; //!< @todo documentation + uint8_t sec; //!< @todo documentation + uint8_t valid; //!< @todo documentation +}; // clang-format on + +static_assert(sizeof(UBX_NAV_TIMEUTC_V0_GROUP0) == 20, ""); + +// clang-format off +static constexpr std::size_t UBX_NAV_TIMEUTC_V0_SIZE = sizeof(UBX_NAV_TIMEUTC_V0_GROUP0) + UBX_FRAME_SIZE; //!< @todo documentation +static constexpr double UBX_NAV_TIMEUTC_V0_ITOW_SCALE = 1e-3; //!< @todo documentation +static constexpr double UBX_NAV_TIMEUTC_V0_TACC_SCALE = 1e-9; //!< @todo documentation +static constexpr double UBX_NAV_TIMEUTC_V0_NANO_SCALE = 1e-9; //!< @todo documentation +static constexpr uint8_t UBX_NAV_TIMEUTC_V0_VALID_VALIDTOW(const uint8_t valid) { return (valid & 0x01) == 0x01; } //!< @todo documentation +static constexpr uint8_t UBX_NAV_TIMEUTC_V0_VALID_VALIDWKN(const uint8_t valid) { return (valid & 0x02) == 0x02; } //!< @todo documentation +static constexpr uint8_t UBX_NAV_TIMEUTC_V0_VALID_VALIDUTC(const uint8_t valid) { return (valid & 0x04) == 0x04; } //!< @todo documentation +static constexpr bool UBX_NAV_TIMEUTC_V0_VALID_AUTHSTATUS(const uint8_t valid) { return (valid & 0x08) == 0x08; } //!< @todo documentation +static constexpr uint8_t UBX_NAV_TIMEUTC_V0_VALID_UTCSTANDARD_GET(const uint8_t valid) { return (valid >> 4) & 0x0f; } //!< @todo documentation +static constexpr uint8_t UBX_NAV_TIMEUTC_V0_VALID_UTCSTANDARD_INFONA = 0; //!< @todo documentation +static constexpr uint8_t UBX_NAV_TIMEUTC_V0_VALID_UTCSTANDARD_CRL = 1; //!< @todo documentation +static constexpr uint8_t UBX_NAV_TIMEUTC_V0_VALID_UTCSTANDARD_NIST = 2; //!< @todo documentation +static constexpr uint8_t UBX_NAV_TIMEUTC_V0_VALID_UTCSTANDARD_USNO = 3; //!< @todo documentation +static constexpr uint8_t UBX_NAV_TIMEUTC_V0_VALID_UTCSTANDARD_BIPM = 4; //!< @todo documentation +static constexpr uint8_t UBX_NAV_TIMEUTC_V0_VALID_UTCSTANDARD_EU = 5; //!< @todo documentation +static constexpr uint8_t UBX_NAV_TIMEUTC_V0_VALID_UTCSTANDARD_SU = 6; //!< @todo documentation +static constexpr uint8_t UBX_NAV_TIMEUTC_V0_VALID_UTCSTANDARD_NTSC = 7; //!< @todo documentation +static constexpr uint8_t UBX_NAV_TIMEUTC_V0_VALID_UTCSTANDARD_NPLI = 8; //!< @todo documentation +static constexpr uint8_t UBX_NAV_TIMEUTC_V0_VALID_UTCSTANDARD_UNNOWN = 15; //!< @todo documentation +// clang-format on + +///@} +// --------------------------------------------------------------------------------------------------------------------- +/** + * @name UBX-NAV-TIMELS message + * @{ + */ + +//! UBX-NAV-TIMELS payload +struct UBX_NAV_TIMELS_V0_GROUP0 // clang-format off +{ + uint32_t iTOW; //!< @todo documentation + uint8_t version; //!< @todo documentation + uint8_t reserved0[3]; //!< @todo documentation + uint8_t srcOfCurrLs; //!< @todo documentation + int8_t currLs; //!< @todo documentation + uint8_t srcOfLsChange; //!< @todo documentation + int8_t lsChange; //!< @todo documentation + int32_t timeToLsEvent; //!< @todo documentation + uint16_t dateOfLsGpsWn; //!< @todo documentation + uint16_t dateOfLsGpsDn; //!< @todo documentation + uint8_t reserved1[3]; //!< @todo documentation + uint8_t valid; //!< @todo documentation +}; // clang-format on + +static_assert(sizeof(UBX_NAV_TIMELS_V0_GROUP0) == 24, ""); + +// clang-format off +static constexpr std::size_t UBX_NAV_TIMELS_V0_SIZE = sizeof(UBX_NAV_TIMELS_V0_GROUP0) + UBX_FRAME_SIZE; //!< @todo documentation +static constexpr double UBX_NAV_TIMELS_V0_ITOW_SCALE = 1e-3; //!< @todo documentation +static constexpr uint8_t UBX_NAV_TIMELS_V0_SRCOFCURRLS_DEFAULT = 0; //!< @todo documentation +static constexpr uint8_t UBX_NAV_TIMELS_V0_SRCOFCURRLS_GPSGLO = 1; //!< @todo documentation +static constexpr uint8_t UBX_NAV_TIMELS_V0_SRCOFCURRLS_GPS = 2; //!< @todo documentation +static constexpr uint8_t UBX_NAV_TIMELS_V0_SRCOFCURRLS_SBAS = 3; //!< @todo documentation +static constexpr uint8_t UBX_NAV_TIMELS_V0_SRCOFCURRLS_BDS = 4; //!< @todo documentation +static constexpr uint8_t UBX_NAV_TIMELS_V0_SRCOFCURRLS_GAL = 5; //!< @todo documentation +static constexpr uint8_t UBX_NAV_TIMELS_V0_SRCOFCURRLS_CONFIG = 7; //!< @todo documentation +static constexpr uint8_t UBX_NAV_TIMELS_V0_SRCOFCURRLS_UNKNOWN = 255; //!< @todo documentation +static constexpr uint8_t UBX_NAV_TIMELS_V0_SRCOFCURRLSCHANGE_NONE = 0; //!< @todo documentation +static constexpr uint8_t UBX_NAV_TIMELS_V0_SRCOFCURRLSCHANGE_GPS = 2; //!< @todo documentation +static constexpr uint8_t UBX_NAV_TIMELS_V0_SRCOFCURRLSCHANGE_SBAS = 3; //!< @todo documentation +static constexpr uint8_t UBX_NAV_TIMELS_V0_SRCOFCURRLSCHANGE_BDS = 4; //!< @todo documentation +static constexpr uint8_t UBX_NAV_TIMELS_V0_SRCOFCURRLSCHANGE_GAL = 5; //!< @todo documentation +static constexpr uint8_t UBX_NAV_TIMELS_V0_SRCOFCURRLSCHANGE_GLO = 6; //!< @todo documentation +static constexpr bool UBX_NAV_TIMELS_V0_VALID_CURRLSVALID(const uint8_t valid) { return (valid & 0x01) == 0x01; } //!< @todo documentation +static constexpr bool UBX_NAV_TIMELS_V0_VALID_TIMETOLSEVENTVALID(const uint8_t valid) { return (valid & 0x02) == 0x02; } //!< @todo documentation +// clang-format on + +///@} +// --------------------------------------------------------------------------------------------------------------------- +/** + * @name UBX-NAV-VELECEF message + * @{ + */ + +//! UBX-NAV-VELECEF payload +struct UBX_NAV_VELECEF_V0_GROUP0 // clang-format off +{ + uint32_t iTOW; //!< @todo documentation + int32_t ecefVX; //!< @todo documentation + int32_t ecefVY; //!< @todo documentation + int32_t ecefVZ; //!< @todo documentation + uint32_t sAcc; //!< @todo documentation +}; // clang-format on + +static_assert(sizeof(UBX_NAV_VELECEF_V0_GROUP0) == 20, ""); + +// clang-format off +static constexpr std::size_t UBX_NAV_VELECEF_V0_SIZE = sizeof(UBX_NAV_VELECEF_V0_GROUP0) + UBX_FRAME_SIZE; //!< @todo documentation +static constexpr double UBX_NAV_VELECEF_V0_ITOW_SCALE = 1e-3; //!< @todo documentation +static constexpr double UBX_NAV_VELECEF_V0_ECEF_XYZ_SCALE = 1e-2; //!< @todo documentation +static constexpr double UBX_NAV_VELECEF_V0_SACC_SCALE = 1e-2; //!< @todo documentation +// clang-format on + +///@} + +// --------------------------------------------------------------------------------------------------------------------- +/** + * @name UBX-RXM-RAWX message + * @{ + */ + +//! UBX-RXM-RAWX (version 1, output) payload head +struct UBX_RXM_RAWX_V1_GROUP0 // clang-format off +{ + double rcvTow; //!< @todo documentation + uint16_t week; //!< @todo documentation + int8_t leapS; //!< @todo documentation + uint8_t numMeas; //!< @todo documentation + uint8_t recStat; //!< @todo documentation + uint8_t version; //!< @todo documentation + uint8_t reserved[2]; //!< @todo documentation +}; // clang-format on + +static_assert(sizeof(UBX_RXM_RAWX_V1_GROUP0) == 16, ""); + +//! UBX-RXM-RAWX (version 1, output) payload repeated group +struct UBX_RXM_RAWX_V1_GROUP1 // clang-format off +{ + double prMeas; //!< @todo documentation + double cpMeas; //!< @todo documentation + float doMeas; //!< @todo documentation + uint8_t gnssId; //!< @todo documentation + uint8_t svId; //!< @todo documentation + uint8_t sigId; //!< @todo documentation + uint8_t freqId; //!< @todo documentation + uint16_t locktime; //!< @todo documentation + uint8_t cno; //!< @todo documentation + uint8_t prStdev; //!< @todo documentation + uint8_t cpStdev; //!< @todo documentation + uint8_t doStdev; //!< @todo documentation + uint8_t trkStat; //!< @todo documentation + uint8_t reserved[1]; //!< @todo documentation +}; // clang-format on + +static_assert(sizeof(UBX_RXM_RAWX_V1_GROUP1) == 32, ""); + +// clang-format off +static constexpr uint8_t UBX_RXM_RAWX_VERSION_GET(const uint8_t* msg) { return msg[UBX_HEAD_SIZE + 13]; } //!< @todo documentation +static constexpr uint8_t UBX_RXM_RAWX_V1_VERSION = 0x01; //!< @todo documentation +static constexpr std::size_t UBX_RXM_RAWX_V1_MIN_SIZE = sizeof(UBX_RXM_RAWX_V1_GROUP0) + UBX_FRAME_SIZE; //!< @todo documentation +static constexpr bool UBX_RXM_RAWX_V1_RECSTAT_LEAPSEC(const uint8_t recStat) { return (recStat & 0x01) == 0x01; } //!< @todo documentation +static constexpr bool UBX_RXM_RAWX_V1_RECSTAT_CLKRESET(const uint8_t recStat) { return (recStat & 0x02) == 0x02; } //!< @todo documentation +static constexpr uint8_t UBX_RXM_RAWX_V1_PRSTDEV_PRSTD_GET(const uint8_t prStdev) { return prStdev & 0x0f; } //!< @todo documentation +static constexpr double UBX_RXM_RAWX_V1_PRSTD_SCALE(const double prStd) { return 0.01 * std::exp2(prStd); } //!< @todo documentation +static constexpr uint8_t UBX_RXM_RAWX_V1_CPSTDEV_CPSTD_GET(const uint8_t cpStdev) { return cpStdev & 0x0f; } //!< @todo documentation +static constexpr double UBX_RXM_RAWX_V1_CPSTD_SCALE(const double cpStd) { return 0.004 * cpStd; } //!< @todo documentation +static constexpr uint8_t UBX_RXM_RAWX_V1_DOSTDEV_DOSTD_GET(const uint8_t doStdev) { return doStdev & 0x0f; } //!< @todo documentation +static constexpr double UBX_RXM_RAWX_V1_DOSTD_SCALE(const double doStd) { return 0.002 * std::exp2(doStd); } //!< @todo documentation +static constexpr double UBX_RXM_RAWX_V1_LOCKTIME_SCALE = 1e-3; //!< @todo documentation +static constexpr bool UBX_RXM_RAWX_V1_TRKSTAT_PRVALID(const uint8_t trkStat) { return (trkStat & 0x01) == 0x01; } //!< @todo documentation +static constexpr bool UBX_RXM_RAWX_V1_TRKSTAT_CPVALID(const uint8_t trkStat) { return (trkStat & 0x02) == 0x02; } //!< @todo documentation +static constexpr bool UBX_RXM_RAWX_V1_TRKSTAT_HALFCYC(const uint8_t trkStat) { return (trkStat & 0x04) == 0x04; } //!< @todo documentation +static constexpr bool UBX_RXM_RAWX_V1_TRKSTAT_SUBHALFCYC(const uint8_t trkStat) { return (trkStat & 0x08) == 0x08; } //!< @todo documentation +static constexpr std::size_t UBX_RXM_RAWX_V1_SIZE(const uint8_t *msg) { return + ((sizeof(UBX_RXM_RAWX_V1_GROUP0) + UBX_FRAME_SIZE + (((uint8_t *)(msg))[UBX_HEAD_SIZE + 11] * sizeof(UBX_RXM_RAWX_V1_GROUP1)))); } //!< @todo documentation + +// clang-format on + +///@} +// --------------------------------------------------------------------------------------------------------------------- +/** + * @name UBX-RXM-RTCM message + * @{ + */ + +//! UBX-RXM-RTCM (version 2, output) +struct UBX_RXM_RTCM_V2_GROUP0 // clang-format off +{ + uint8_t version; //!< @todo documentation + uint8_t flags; //!< @todo documentation + uint16_t subType; //!< @todo documentation + uint16_t refStation; //!< @todo documentation + uint16_t msgType; //!< @todo documentation +}; // clang-format on + +static_assert(sizeof(UBX_RXM_RTCM_V2_GROUP0) == 8, ""); + +// clang-format off +static constexpr uint8_t UBX_RXM_RTCM_VERSION_GET(const uint8_t* msg) { return msg[UBX_HEAD_SIZE]; } //!< @todo documentation +static constexpr uint8_t UBX_RXM_RTCM_V2_VERSION = 0x02; //!< @todo documentation +static constexpr std::size_t UBX_RXM_RTCM_V2_SIZE = sizeof(UBX_RXM_RTCM_V2_GROUP0) + UBX_FRAME_SIZE; //!< @todo documentation +static constexpr bool UBX_RXM_RTCM_V2_FLAGS_CRCFAILED(const uint8_t flags) { return (flags & 0x01) == 0x01; } //!< @todo documentation +static constexpr uint8_t UBX_RXM_RTCM_V2_FLAGS_MSGUSED_GET(const uint8_t flags) { return (flags >> 1) & 0x03; } //!< @todo documentation +static constexpr uint8_t UBX_RXM_RTCM_V2_FLAGS_MSGUSED_UNKNOWN = 0x00; //!< @todo documentation +static constexpr uint8_t UBX_RXM_RTCM_V2_FLAGS_MSGUSED_UNUSED = 0x01; //!< @todo documentation +static constexpr uint8_t UBX_RXM_RTCM_V2_FLAGS_MSGUSED_USED = 0x02; //!< @todo documentation +// clang-format on + +///@} +// --------------------------------------------------------------------------------------------------------------------- +/** + * @name UBX-RXM-SFRBX message + * @{ + */ + +//! UBX-RXM-SFRBX (version 2, output) payload head +struct UBX_RXM_SFRBX_V2_GROUP0 // clang-format off +{ + uint8_t gnssId; //!< @todo documentation + uint8_t svId; //!< @todo documentation + uint8_t sigId; //!< interface description says "reserved", but u-center says "sigId"... + uint8_t freqId; //!< @todo documentation + uint8_t numWords; //!< @todo documentation + uint8_t chn; //!< @todo documentation + uint8_t version; //!< @todo documentation + uint8_t reserved1; //!< @todo documentation +}; // clang-format on + +static_assert(sizeof(UBX_RXM_SFRBX_V2_GROUP0) == 8, ""); + +//! UBX-RXM-SFRBX (version 2, output) payload repeated group +struct UBX_RXM_SFRBX_V2_GROUP1 // clang-format off +{ + uint32_t dwrd; //!< @todo documentation +}; // clang-format on + +static_assert(sizeof(UBX_RXM_SFRBX_V2_GROUP1) == 4, ""); + +// clang-format off +static constexpr uint8_t UBX_RXM_SFRBX_VERSION_GET(const uint8_t* msg) { return msg[UBX_HEAD_SIZE + 6]; } //!< @todo documentation +static constexpr uint8_t UBX_RXM_SFRBX_V2_VERSION = 0x02; //!< @todo documentation +static constexpr std::size_t UBX_RXM_SFRBX_V2_MIN_SIZE = sizeof(UBX_RXM_SFRBX_V2_GROUP0) + UBX_FRAME_SIZE; //!< @todo documentation +// clang-format on + +///@} + +// --------------------------------------------------------------------------------------------------------------------- +/** + * @name UBX-RXM-SPARTN message + * @{ + */ + +//! UBX-RXM-SPARTN (version 1, output) +struct UBX_RXM_SPARTN_V1_GROUP0 // clang-format off +{ + uint8_t version; //!< @todo documentation + uint8_t flags; //!< @todo documentation + uint16_t subType; //!< @todo documentation + uint8_t reserved[2]; //!< @todo documentation + uint16_t msgType; //!< @todo documentation +}; // clang-format on + +// clang-format off +static constexpr uint8_t UBX_RXM_SPARTN_VERSION_GET(const uint8_t* msg) { return msg[UBX_HEAD_SIZE]; } //!< @todo documentation +static constexpr uint8_t UBX_RXM_SPARTN_V1_VERSION = 0x01; //!< @todo documentation +static constexpr std::size_t UBX_RXM_SPARTN_V1_SIZE = sizeof(UBX_RXM_SPARTN_V1_GROUP0) + UBX_FRAME_SIZE; //!< @todo documentation +static constexpr uint8_t UBX_RXM_SPARTN_V1_FLAGS_MSGUSED_GET(const uint8_t flags) { return (flags >> 1) & 0x03; } //!< @todo documentation +static constexpr uint8_t UBX_RXM_SPARTN_V1_FLAGS_MSGUSED_UNKNOWN = 0x00; //!< @todo documentation +static constexpr uint8_t UBX_RXM_SPARTN_V1_FLAGS_MSGUSED_UNUSED = 0x01; //!< @todo documentation +static constexpr uint8_t UBX_RXM_SPARTN_V1_FLAGS_MSGUSED_USED = 0x02; //!< @todo documentation +// clang-format on + +///@} +// --------------------------------------------------------------------------------------------------------------------- +/** + * @name UBX-TIM-SVIN message + * @{ + */ + +//! UBX-TIM_SVIN payload +struct UBX_TIM_SVIN_V0_GROUP0 // clang-format off +{ + uint32_t dur; //!< @todo documentation + int32_t meanX; //!< @todo documentation + int32_t meanY; //!< @todo documentation + int32_t meanZ; //!< @todo documentation + uint32_t meanV; //!< @todo documentation + uint32_t obs; //!< @todo documentation + uint8_t valid; //!< @todo documentation + uint8_t active; //!< @todo documentation + uint16_t reserved; //!< @todo documentation +}; // clang-format on + +static_assert(sizeof(UBX_TIM_SVIN_V0_GROUP0) == 28, ""); + +// clang-format off +static constexpr std::size_t UBX_TIM_SVIN_V0_SIZE = sizeof(UBX_TIM_SVIN_V0_GROUP0) + UBX_FRAME_SIZE; //!< @todo documentation +// clang-format on + +///@} +// --------------------------------------------------------------------------------------------------------------------- +/** + * @name UBX-TIM-TM2 message + * @{ + */ + +//! UBX-TIM-TM2 payload +struct UBX_TIM_TM2_V0_GROUP0 // clang-format off +{ + uint8_t ch; //!< @todo documentation + uint8_t flags; //!< @todo documentation + uint16_t count; //!< @todo documentation + uint16_t wnR; //!< @todo documentation + uint16_t wnF; //!< @todo documentation + uint32_t towMsR; //!< @todo documentation + uint32_t towSubMsR; //!< @todo documentation + uint32_t towMsF; //!< @todo documentation + uint32_t towSubMsF; //!< @todo documentation + uint32_t accEst; //!< @todo documentation +}; // clang-format on + +static_assert(sizeof(UBX_TIM_TM2_V0_GROUP0) == 28, ""); + +// clang-format off +static constexpr std::size_t UBX_TIM_TM2_V0_SIZE = sizeof(UBX_TIM_TM2_V0_GROUP0) + UBX_FRAME_SIZE; //!< @todo documentation +static constexpr uint8_t UBX_TIM_TM2_V0_FLAGS_MODE_GET(const uint8_t flags) { return flags & 0x01; } //!< @todo documentation +static constexpr uint8_t UBX_TIM_TM2_V0_FLAGS_MODE_SINGLE = 0; //!< @todo documentation +static constexpr uint8_t UBX_TIM_TM2_V0_FLAGS_MODE_RUNNING = 1; //!< @todo documentation +static constexpr uint8_t UBX_TIM_TM2_V0_FLAGS_RUN_GET(const uint8_t flags) { return (flags >> 1) & 0x01; } //!< @todo documentation +static constexpr uint8_t UBX_TIM_TM2_V0_FLAGS_RUN_ARMED = 0; //!< @todo documentation +static constexpr uint8_t UBX_TIM_TM2_V0_FLAGS_RUN_STOPPED = 1; //!< @todo documentation +static constexpr bool UBX_TIM_TM2_V0_FLAGS_NEWFALLINGEDGE(const uint8_t flags) { return (flags & 0x04) == 0x04; } //!< @todo documentation +static constexpr uint8_t UBX_TIM_TM2_V0_FLAGS_TIMEBASE_GET(const uint8_t flags) { return (flags >> 3) & 0x03; } //!< @todo documentation +static constexpr uint8_t UBX_TIM_TM2_V0_FLAGS_TIMEBASE_RX = 0; //!< @todo documentation +static constexpr uint8_t UBX_TIM_TM2_V0_FLAGS_TIMEBASE_GNSS = 1; //!< @todo documentation +static constexpr uint8_t UBX_TIM_TM2_V0_FLAGS_TIMEBASE_UTC = 2; //!< @todo documentation +static constexpr bool UBX_TIM_TM2_V0_FLAGS_UTCACAVAIL(const uint8_t flags) { return (flags & 0x20) == 0x20; } //!< @todo documentation +static constexpr bool UBX_TIM_TM2_V0_FLAGS_TIMEVALID(const uint8_t flags) { return (flags & 0x40) == 0x40; } //!< @todo documentation +static constexpr bool UBX_TIM_TM2_V0_FLAGS_NEWRISINGEDGE(const uint8_t flags) { return (flags & 0x80) == 0x80; } //!< @todo documentation +static constexpr double UBX_TIM_TM2_V0_TOW_SCALE = 1e-3; //!< @todo documentation +static constexpr double UBX_TIM_TM2_V0_SUBMS_SCALE = 1e-9; //!< @todo documentation +static constexpr double UBX_TIM_TM2_V0_ACCEST_SCALE = 1e-9; //!< @todo documentation +// clang-format on + +///@} +// --------------------------------------------------------------------------------------------------------------------- +/** + * @name UBX-TIM_TP message + * @{ + */ + +//! UBX-TIM-TP payload +struct UBX_TIM_TP_V0_GROUP0 // clang-format off +{ + uint32_t towMs; //!< @todo documentation + uint32_t towSubMs; //!< @todo documentation + int32_t qErr; //!< @todo documentation + uint16_t week; //!< @todo documentation + uint8_t flags; //!< @todo documentation + uint8_t refInfo; //!< @todo documentation +}; // clang-format on + +static_assert(sizeof(UBX_TIM_TP_V0_GROUP0) == 16, ""); + +// clang-format off +static constexpr std::size_t UBX_TIM_TP_V0_SIZE = sizeof(UBX_TIM_TP_V0_GROUP0) + UBX_FRAME_SIZE; //!< @todo documentation +static constexpr double UBX_TIM_TP_V0_TOWMS_SCALE = 1e-3; //!< @todo documentation +static constexpr double UBX_TIM_TP_V0_TOWSUBMS_SCALE = 0x1.0624dd2f1a9fcp-42; //!< perl -e 'printf "%a", 2**-32 * 1e-3' +static constexpr double UBX_TIM_TP_V0_TOWSUBMS_SCALE_APPROX = 2.3283064365386963e-18; //!< perl -e 'printf "%.18g", 2**-32 * 1e-8' +static constexpr uint8_t UBX_TIM_TP_V0_FLAGS_TIMEBASE_GET(const uint8_t flags) { return flags & 0x01; } //!< @todo documentation +static constexpr uint8_t UBX_TIM_TP_V0_FLAGS_TIMEBASE_GNSS = 0; //!< @todo documentation +static constexpr uint8_t UBX_TIM_TP_V0_FLAGS_TIMEBASE_UTC = 1; //!< @todo documentation +static constexpr bool UBX_TIM_TP_V0_FLAGS_UTC(const uint8_t flags) { return (flags & 0x02) == 0x02; } //!< @todo documentation +static constexpr uint8_t UBX_TIM_TP_V0_FLAGS_RAIM_GET(const uint8_t flags) { return (flags >> 2) & 0x03; } //!< @todo documentation +static constexpr uint8_t UBX_TIM_TP_V0_FLAGS_RAIM_NA = 0; //!< @todo documentation +static constexpr uint8_t UBX_TIM_TP_V0_FLAGS_RAIM_INACTIVE = 1; //!< @todo documentation +static constexpr uint8_t UBX_TIM_TP_V0_FLAGS_RAIM_ACTIVE = 2; //!< @todo documentation +static constexpr bool UBX_TIM_TP_V0_FLAGS_QERRINVALID(const uint8_t flags) { return (flags & 0x10) == 0x10; } //!< @todo documentation +static constexpr bool UBX_TIM_TP_V0_FLAGS_TPNOTLOCKED(const uint8_t flags) { return (flags & 0x20) == 0x20; } //!< @todo documentation +static constexpr uint8_t UBX_TIM_TP_V0_REFINFO_TIMEREFGNSS_GET(const uint8_t refInfo) { return refInfo & 0x0f; } //!< @todo documentation +static constexpr uint8_t UBX_TIM_TP_V0_REFINFO_TIMEREFGNSS_GPS = 0; //!< @todo documentation +static constexpr uint8_t UBX_TIM_TP_V0_REFINFO_TIMEREFGNSS_GLO = 1; //!< @todo documentation +static constexpr uint8_t UBX_TIM_TP_V0_REFINFO_TIMEREFGNSS_BDS = 2; //!< @todo documentation +static constexpr uint8_t UBX_TIM_TP_V0_REFINFO_TIMEREFGNSS_GAL = 3; //!< @todo documentation +static constexpr uint8_t UBX_TIM_TP_V0_REFINFO_TIMEREFGNSS_NAVIC = 4; //!< @todo documentation +static constexpr uint8_t UBX_TIM_TP_V0_REFINFO_TIMEREFGNSS_UNKNOWN = 15; //!< @todo documentation +static constexpr uint8_t UBX_TIM_TP_V0_REFINFO_UTCSTANDARD_GET(const uint8_t refInfo) { return (refInfo >> 4) & 0x0f; } //!< @todo documentation +static constexpr uint8_t UBX_TIM_TP_V0_REFINFO_UTCSTANDARD_INFONA = 0; //!< @todo documentation +static constexpr uint8_t UBX_TIM_TP_V0_REFINFO_UTCSTANDARD_CRL = 1; //!< @todo documentation +static constexpr uint8_t UBX_TIM_TP_V0_REFINFO_UTCSTANDARD_NIST = 2; //!< @todo documentation +static constexpr uint8_t UBX_TIM_TP_V0_REFINFO_UTCSTANDARD_USNO = 3; //!< @todo documentation +static constexpr uint8_t UBX_TIM_TP_V0_REFINFO_UTCSTANDARD_BIPM = 4; //!< @todo documentation +static constexpr uint8_t UBX_TIM_TP_V0_REFINFO_UTCSTANDARD_EU = 5; //!< @todo documentation +static constexpr uint8_t UBX_TIM_TP_V0_REFINFO_UTCSTANDARD_SU = 6; //!< @todo documentation +static constexpr uint8_t UBX_TIM_TP_V0_REFINFO_UTCSTANDARD_NTSC = 7; //!< @todo documentation +static constexpr uint8_t UBX_TIM_TP_V0_REFINFO_UTCSTANDARD_NPLI = 8; //!< @todo documentation +static constexpr uint8_t UBX_TIM_TP_V0_REFINFO_UTCSTANDARD_UNNOWN = 15; //!< @todo documentation +// clang-format on + +///@} +// --------------------------------------------------------------------------------------------------------------------- + +#undef UBX_PACKED + +/* ****************************************************************************************************************** */ +} // namespace ubx +} // namespace parser +} // namespace common +} // namespace fpsdk +#endif // __FPSDK_COMMON_PARSER_UBX_HPP__ diff --git a/fpsdk_common/include/fpsdk_common/parser/unib.hpp b/fpsdk_common/include/fpsdk_common/parser/unib.hpp new file mode 100644 index 0000000..597969d --- /dev/null +++ b/fpsdk_common/include/fpsdk_common/parser/unib.hpp @@ -0,0 +1,396 @@ +/** + * \verbatim + * ___ ___ + * \ \ / / + * \ \/ / Copyright (c) Fixposition AG (www.fixposition.com) and contributors + * / /\ \ License: see the LICENSE file + * /__/ \__\ + * + * Based on work by flipflip (https://github.com/phkehl) + * The information on message structures, IDs, descriptions etc. in this file are from publicly available data, such as: + * - Unicore Standard Position Protocol, copyright (c) 2009-2023, Unicore Communications, Inc. + * - Unicore High Precision Commands and Logs, Copyright (c) 2009-2021, Unicore Communications, Inc. + * \endverbatim + * + * @file + * @brief Fixposition SDK: Parser UNI_B routines and types + * + * @page FPSDK_COMMON_PARSER_UNIB Parser UNI_B routines and types + * + * **API**: fpsdk_common/parser/unib.hpp and fpsdk::common::parser::unib + * + */ +#ifndef __FPSDK_COMMON_PARSER_UNIB_HPP__ +#define __FPSDK_COMMON_PARSER_UNIB_HPP__ + +/* LIBC/STL */ +#include + +/* EXTERNAL */ + +/* PACKAGE */ +#include "novb.hpp" + +namespace fpsdk { +namespace common { +namespace parser { +/** + * @brief Parser UNI_B routines and types + */ +namespace unib { +/* ****************************************************************************************************************** */ + +static constexpr uint8_t UNI_B_SYNC_1 = 0xaa; //!< Sync char 1 +static constexpr uint8_t UNI_B_SYNC_2 = 0x44; //!< Sync char 2 +static constexpr uint8_t UNI_B_SYNC_3 = 0xb5; //!< Sync char 3 +static constexpr std::size_t UNI_B_HEAD_SIZE = 24; //!< Size of the UNI_B header (UnibHeader) + +/** + * @brief Get message ID + * + * @param[in] msg Pointer to the start of the message + * + * @note No check on the data provided is done. The caller must ensure that the data is a valid UNI_B message. + * + * @returns the message ID + */ +constexpr uint16_t UnibMsgId(const uint8_t* msg) +{ + return (((uint16_t)((uint8_t*)msg)[5] << 8) | (uint16_t)((uint8_t*)msg)[4]); +} + +/** + * @brief Get message size + * + * @param[in] msg Pointer to the start of the message + * + * @note No check on the data provided is done. The caller must ensure that the data is a valid UNI_B message. + * + * @returns the message size + */ +constexpr uint16_t UnibMsgSize(const uint8_t* msg) +{ + return (((uint16_t)((uint8_t*)msg)[7] << 8) | (uint16_t)((uint8_t*)msg)[6]); +} + +/** + * @brief Get message version + * + * @param[in] msg Pointer to the start of the message + * + * @note No check on the data provided is done. The caller must ensure that the data is a valid UNI_B message. + * + * @returns the message version + */ +constexpr uint8_t UNI_B_MSGVER(const uint8_t* msg) +{ + return msg[20]; +} + +/** + * @brief Get UNI_B message name + * + * Generates a name (string) in the form "UNI_B-NAME", where NAME is a suitable stringifications of the + * message ID if known (for example, "UNI_B-BESTNAV", respectively "%05u" formatted message ID if unknown (for + * example, "UNI_B-MSG01234"). + * + * @param[out] name String to write the name to + * @param[in] size Size of \c name (incl. nul termination) + * @param[in] msg Pointer to the UNI_B message + * @param[in] msg_size Size of the \c msg + * + * @note No check on the data provided is done. The caller must ensure that the data is a valid UNI_B message. + * + * @returns true if message name was generated, false if \c name buffer was too small + */ +bool UnibGetMessageName(char* name, const std::size_t size, const uint8_t* msg, const std::size_t msg_size); + +/** + * @brief Get UNI_B message info + * + * This stringifies the content of some UNI_B messages, for debugging. + * + * @param[out] info String to write the info to + * @param[in] size Size of \c name (incl. nul termination) + * @param[in] msg Pointer to the UNI_B message + * @param[in] msg_size Size of the \c msg + * + * @note No check on the data provided is done. The caller must ensure that the data is a valid UNI_B message. + * + * @returns true if message info was generated (even if info is empty), false if \c name buffer was too small + */ +bool UnibGetMessageInfo(char* info, const std::size_t size, const uint8_t* msg, const std::size_t msg_size); + +// --------------------------------------------------------------------------------------------------------------------- + +/** + * @name UNI_B messages (names and IDs) + * + * @{ + */ +// clang-format off +// @fp_codegen_begin{FPSDK_COMMON_PARSER_UNIB_MESSAGES} +static constexpr uint16_t UNI_B_VERSION_MSGID = 37; //!< UNI_B-VERSION message ID +static constexpr const char* UNI_B_VERSION_STRID = "UNI_B-VERSION"; //!< UNI_B-VERSION message name +static constexpr uint16_t UNI_B_OBSVM_MSGID = 12; //!< UNI_B-OBSVM message ID +static constexpr const char* UNI_B_OBSVM_STRID = "UNI_B-OBSVM"; //!< UNI_B-OBSVM message name +static constexpr uint16_t UNI_B_OBSVH_MSGID = 13; //!< UNI_B-OBSVH message ID +static constexpr const char* UNI_B_OBSVH_STRID = "UNI_B-OBSVH"; //!< UNI_B-OBSVH message name +static constexpr uint16_t UNI_B_OBSVMCMP_MSGID = 138; //!< UNI_B-OBSVMCMP message ID +static constexpr const char* UNI_B_OBSVMCMP_STRID = "UNI_B-OBSVMCMP"; //!< UNI_B-OBSVMCMP message name +static constexpr uint16_t UNI_B_OBSVHCMP_MSGID = 139; //!< UNI_B-OBSVHCMP message ID +static constexpr const char* UNI_B_OBSVHCMP_STRID = "UNI_B-OBSVHCMP"; //!< UNI_B-OBSVHCMP message name +static constexpr uint16_t UNI_B_OBSVBASE_MSGID = 284; //!< UNI_B-OBSVBASE message ID +static constexpr const char* UNI_B_OBSVBASE_STRID = "UNI_B-OBSVBASE"; //!< UNI_B-OBSVBASE message name +static constexpr uint16_t UNI_B_BASEINFO_MSGID = 176; //!< UNI_B-BASEINFO message ID +static constexpr const char* UNI_B_BASEINFO_STRID = "UNI_B-BASEINFO"; //!< UNI_B-BASEINFO message name +static constexpr uint16_t UNI_B_GPSION_MSGID = 8; //!< UNI_B-GPSION message ID +static constexpr const char* UNI_B_GPSION_STRID = "UNI_B-GPSION"; //!< UNI_B-GPSION message name +static constexpr uint16_t UNI_B_BD3ION_MSGID = 21; //!< UNI_B-BD3ION message ID +static constexpr const char* UNI_B_BD3ION_STRID = "UNI_B-BD3ION"; //!< UNI_B-BD3ION message name +static constexpr uint16_t UNI_B_BDSION_MSGID = 4; //!< UNI_B-BDSION message ID +static constexpr const char* UNI_B_BDSION_STRID = "UNI_B-BDSION"; //!< UNI_B-BDSION message name +static constexpr uint16_t UNI_B_GALION_MSGID = 9; //!< UNI_B-GALION message ID +static constexpr const char* UNI_B_GALION_STRID = "UNI_B-GALION"; //!< UNI_B-GALION message name +static constexpr uint16_t UNI_B_GPSUTC_MSGID = 19; //!< UNI_B-GPSUTC message ID +static constexpr const char* UNI_B_GPSUTC_STRID = "UNI_B-GPSUTC"; //!< UNI_B-GPSUTC message name +static constexpr uint16_t UNI_B_BD3UTC_MSGID = 22; //!< UNI_B-BD3UTC message ID +static constexpr const char* UNI_B_BD3UTC_STRID = "UNI_B-BD3UTC"; //!< UNI_B-BD3UTC message name +static constexpr uint16_t UNI_B_BDSUTC_MSGID = 2012; //!< UNI_B-BDSUTC message ID +static constexpr const char* UNI_B_BDSUTC_STRID = "UNI_B-BDSUTC"; //!< UNI_B-BDSUTC message name +static constexpr uint16_t UNI_B_GALUTC_MSGID = 20; //!< UNI_B-GALUTC message ID +static constexpr const char* UNI_B_GALUTC_STRID = "UNI_B-GALUTC"; //!< UNI_B-GALUTC message name +static constexpr uint16_t UNI_B_GPSEPH_MSGID = 106; //!< UNI_B-GPSEPH message ID +static constexpr const char* UNI_B_GPSEPH_STRID = "UNI_B-GPSEPH"; //!< UNI_B-GPSEPH message name +static constexpr uint16_t UNI_B_QZSSEPH_MSGID = 110; //!< UNI_B-QZSSEPH message ID +static constexpr const char* UNI_B_QZSSEPH_STRID = "UNI_B-QZSSEPH"; //!< UNI_B-QZSSEPH message name +static constexpr uint16_t UNI_B_BD3EPH_MSGID = 2999; //!< UNI_B-BD3EPH message ID +static constexpr const char* UNI_B_BD3EPH_STRID = "UNI_B-BD3EPH"; //!< UNI_B-BD3EPH message name +static constexpr uint16_t UNI_B_BDSEPH_MSGID = 108; //!< UNI_B-BDSEPH message ID +static constexpr const char* UNI_B_BDSEPH_STRID = "UNI_B-BDSEPH"; //!< UNI_B-BDSEPH message name +static constexpr uint16_t UNI_B_GLOEPH_MSGID = 107; //!< UNI_B-GLOEPH message ID +static constexpr const char* UNI_B_GLOEPH_STRID = "UNI_B-GLOEPH"; //!< UNI_B-GLOEPH message name +static constexpr uint16_t UNI_B_GALEPH_MSGID = 109; //!< UNI_B-GALEPH message ID +static constexpr const char* UNI_B_GALEPH_STRID = "UNI_B-GALEPH"; //!< UNI_B-GALEPH message name +static constexpr uint16_t UNI_B_AGRIC_MSGID = 1276; //!< UNI_B-AGRIC message ID +static constexpr const char* UNI_B_AGRIC_STRID = "UNI_B-AGRIC"; //!< UNI_B-AGRIC message name +static constexpr uint16_t UNI_B_PVTSLN_MSGID = 1021; //!< UNI_B-PVTSLN message ID +static constexpr const char* UNI_B_PVTSLN_STRID = "UNI_B-PVTSLN"; //!< UNI_B-PVTSLN message name +static constexpr uint16_t UNI_B_BESTNAV_MSGID = 2118; //!< UNI_B-BESTNAV message ID +static constexpr const char* UNI_B_BESTNAV_STRID = "UNI_B-BESTNAV"; //!< UNI_B-BESTNAV message name +static constexpr uint16_t UNI_B_BESTNAVXYZ_MSGID = 240; //!< UNI_B-BESTNAVXYZ message ID +static constexpr const char* UNI_B_BESTNAVXYZ_STRID = "UNI_B-BESTNAVXYZ"; //!< UNI_B-BESTNAVXYZ message name +static constexpr uint16_t UNI_B_BESTNAVH_MSGID = 2119; //!< UNI_B-BESTNAVH message ID +static constexpr const char* UNI_B_BESTNAVH_STRID = "UNI_B-BESTNAVH"; //!< UNI_B-BESTNAVH message name +static constexpr uint16_t UNI_B_BESTNAVXYZH_MSGID = 242; //!< UNI_B-BESTNAVXYZH message ID +static constexpr const char* UNI_B_BESTNAVXYZH_STRID = "UNI_B-BESTNAVXYZH"; //!< UNI_B-BESTNAVXYZH message name +static constexpr uint16_t UNI_B_BESTSAT_MSGID = 1041; //!< UNI_B-BESTSAT message ID +static constexpr const char* UNI_B_BESTSAT_STRID = "UNI_B-BESTSAT"; //!< UNI_B-BESTSAT message name +static constexpr uint16_t UNI_B_ADRNAV_MSGID = 142; //!< UNI_B-ADRNAV message ID +static constexpr const char* UNI_B_ADRNAV_STRID = "UNI_B-ADRNAV"; //!< UNI_B-ADRNAV message name +static constexpr uint16_t UNI_B_ADRNAVH_MSGID = 2117; //!< UNI_B-ADRNAVH message ID +static constexpr const char* UNI_B_ADRNAVH_STRID = "UNI_B-ADRNAVH"; //!< UNI_B-ADRNAVH message name +static constexpr uint16_t UNI_B_PPPNAV_MSGID = 1026; //!< UNI_B-PPPNAV message ID +static constexpr const char* UNI_B_PPPNAV_STRID = "UNI_B-PPPNAV"; //!< UNI_B-PPPNAV message name +static constexpr uint16_t UNI_B_SPPNAV_MSGID = 46; //!< UNI_B-SPPNAV message ID +static constexpr const char* UNI_B_SPPNAV_STRID = "UNI_B-SPPNAV"; //!< UNI_B-SPPNAV message name +static constexpr uint16_t UNI_B_SPPNAVH_MSGID = 2116; //!< UNI_B-SPPNAVH message ID +static constexpr const char* UNI_B_SPPNAVH_STRID = "UNI_B-SPPNAVH"; //!< UNI_B-SPPNAVH message name +static constexpr uint16_t UNI_B_STADOP_MSGID = 954; //!< UNI_B-STADOP message ID +static constexpr const char* UNI_B_STADOP_STRID = "UNI_B-STADOP"; //!< UNI_B-STADOP message name +static constexpr uint16_t UNI_B_STADOPH_MSGID = 2122; //!< UNI_B-STADOPH message ID +static constexpr const char* UNI_B_STADOPH_STRID = "UNI_B-STADOPH"; //!< UNI_B-STADOPH message name +static constexpr uint16_t UNI_B_ADRDOP_MSGID = 953; //!< UNI_B-ADRDOP message ID +static constexpr const char* UNI_B_ADRDOP_STRID = "UNI_B-ADRDOP"; //!< UNI_B-ADRDOP message name +static constexpr uint16_t UNI_B_ADRDOPH_MSGID = 2121; //!< UNI_B-ADRDOPH message ID +static constexpr const char* UNI_B_ADRDOPH_STRID = "UNI_B-ADRDOPH"; //!< UNI_B-ADRDOPH message name +static constexpr uint16_t UNI_B_PPPDOP_MSGID = 1025; //!< UNI_B-PPPDOP message ID +static constexpr const char* UNI_B_PPPDOP_STRID = "UNI_B-PPPDOP"; //!< UNI_B-PPPDOP message name +static constexpr uint16_t UNI_B_SPPDOP_MSGID = 173; //!< UNI_B-SPPDOP message ID +static constexpr const char* UNI_B_SPPDOP_STRID = "UNI_B-SPPDOP"; //!< UNI_B-SPPDOP message name +static constexpr uint16_t UNI_B_SPPDOPH_MSGID = 2120; //!< UNI_B-SPPDOPH message ID +static constexpr const char* UNI_B_SPPDOPH_STRID = "UNI_B-SPPDOPH"; //!< UNI_B-SPPDOPH message name +static constexpr uint16_t UNI_B_SATSINFO_MSGID = 2124; //!< UNI_B-SATSINFO message ID +static constexpr const char* UNI_B_SATSINFO_STRID = "UNI_B-SATSINFO"; //!< UNI_B-SATSINFO message name +static constexpr uint16_t UNI_B_BASEPOS_MSGID = 49; //!< UNI_B-BASEPOS message ID +static constexpr const char* UNI_B_BASEPOS_STRID = "UNI_B-BASEPOS"; //!< UNI_B-BASEPOS message name +static constexpr uint16_t UNI_B_SATELLITE_MSGID = 1042; //!< UNI_B-SATELLITE message ID +static constexpr const char* UNI_B_SATELLITE_STRID = "UNI_B-SATELLITE"; //!< UNI_B-SATELLITE message name +static constexpr uint16_t UNI_B_SATECEF_MSGID = 2115; //!< UNI_B-SATECEF message ID +static constexpr const char* UNI_B_SATECEF_STRID = "UNI_B-SATECEF"; //!< UNI_B-SATECEF message name +static constexpr uint16_t UNI_B_RECTIME_MSGID = 102; //!< UNI_B-RECTIME message ID +static constexpr const char* UNI_B_RECTIME_STRID = "UNI_B-RECTIME"; //!< UNI_B-RECTIME message name +static constexpr uint16_t UNI_B_NOVHEADING_MSGID = 972; //!< UNI_B-NOVHEADING message ID +static constexpr const char* UNI_B_NOVHEADING_STRID = "UNI_B-NOVHEADING"; //!< UNI_B-NOVHEADING message name +static constexpr uint16_t UNI_B_NOVHEADING2_MSGID = 1331; //!< UNI_B-NOVHEADING2 message ID +static constexpr const char* UNI_B_NOVHEADING2_STRID = "UNI_B-NOVHEADING2"; //!< UNI_B-NOVHEADING2 message name +static constexpr uint16_t UNI_B_RTKSTATUS_MSGID = 509; //!< UNI_B-RTKSTATUS message ID +static constexpr const char* UNI_B_RTKSTATUS_STRID = "UNI_B-RTKSTATUS"; //!< UNI_B-RTKSTATUS message name +static constexpr uint16_t UNI_B_AGNSSSTATUS_MSGID = 512; //!< UNI_B-AGNSSSTATUS message ID +static constexpr const char* UNI_B_AGNSSSTATUS_STRID = "UNI_B-AGNSSSTATUS"; //!< UNI_B-AGNSSSTATUS message name +static constexpr uint16_t UNI_B_RTCSTATUS_MSGID = 510; //!< UNI_B-RTCSTATUS message ID +static constexpr const char* UNI_B_RTCSTATUS_STRID = "UNI_B-RTCSTATUS"; //!< UNI_B-RTCSTATUS message name +static constexpr uint16_t UNI_B_JAMSTATUS_MSGID = 511; //!< UNI_B-JAMSTATUS message ID +static constexpr const char* UNI_B_JAMSTATUS_STRID = "UNI_B-JAMSTATUS"; //!< UNI_B-JAMSTATUS message name +static constexpr uint16_t UNI_B_FREQJAMSTATUS_MSGID = 519; //!< UNI_B-FREQJAMSTATUS message ID +static constexpr const char* UNI_B_FREQJAMSTATUS_STRID = "UNI_B-FREQJAMSTATUS"; //!< UNI_B-FREQJAMSTATUS message name +static constexpr uint16_t UNI_B_RTCMSTATUS_MSGID = 2125; //!< UNI_B-RTCMSTATUS message ID +static constexpr const char* UNI_B_RTCMSTATUS_STRID = "UNI_B-RTCMSTATUS"; //!< UNI_B-RTCMSTATUS message name +static constexpr uint16_t UNI_B_HWSTATUS_MSGID = 218; //!< UNI_B-HWSTATUS message ID +static constexpr const char* UNI_B_HWSTATUS_STRID = "UNI_B-HWSTATUS"; //!< UNI_B-HWSTATUS message name +static constexpr uint16_t UNI_B_PPPSTATUS_MSGID = 9000; //!< UNI_B-PPPSTATUS message ID +static constexpr const char* UNI_B_PPPSTATUS_STRID = "UNI_B-PPPSTATUS"; //!< UNI_B-PPPSTATUS message name +static constexpr uint16_t UNI_B_AGC_MSGID = 220; //!< UNI_B-AGC message ID +static constexpr const char* UNI_B_AGC_STRID = "UNI_B-AGC"; //!< UNI_B-AGC message name +static constexpr uint16_t UNI_B_INFOPART1_MSGID = 1019; //!< UNI_B-INFOPART1 message ID +static constexpr const char* UNI_B_INFOPART1_STRID = "UNI_B-INFOPART1"; //!< UNI_B-INFOPART1 message name +static constexpr uint16_t UNI_B_INFOPART2_MSGID = 1020; //!< UNI_B-INFOPART2 message ID +static constexpr const char* UNI_B_INFOPART2_STRID = "UNI_B-INFOPART2"; //!< UNI_B-INFOPART2 message name +static constexpr uint16_t UNI_B_MSPOS_MSGID = 520; //!< UNI_B-MSPOS message ID +static constexpr const char* UNI_B_MSPOS_STRID = "UNI_B-MSPOS"; //!< UNI_B-MSPOS message name +static constexpr uint16_t UNI_B_TROPINFO_MSGID = 2318; //!< UNI_B-TROPINFO message ID +static constexpr const char* UNI_B_TROPINFO_STRID = "UNI_B-TROPINFO"; //!< UNI_B-TROPINFO message name +static constexpr uint16_t UNI_B_PTOBSINFO_MSGID = 221; //!< UNI_B-PTOBSINFO message ID +static constexpr const char* UNI_B_PTOBSINFO_STRID = "UNI_B-PTOBSINFO"; //!< UNI_B-PTOBSINFO message name +static constexpr uint16_t UNI_B_PPPB2INFO1_MSGID = 2302; //!< UNI_B-PPPB2INFO1 message ID +static constexpr const char* UNI_B_PPPB2INFO1_STRID = "UNI_B-PPPB2INFO1"; //!< UNI_B-PPPB2INFO1 message name +static constexpr uint16_t UNI_B_PPPB2INFO2_MSGID = 2304; //!< UNI_B-PPPB2INFO2 message ID +static constexpr const char* UNI_B_PPPB2INFO2_STRID = "UNI_B-PPPB2INFO2"; //!< UNI_B-PPPB2INFO2 message name +static constexpr uint16_t UNI_B_PPPB2INFO3_MSGID = 2306; //!< UNI_B-PPPB2INFO3 message ID +static constexpr const char* UNI_B_PPPB2INFO3_STRID = "UNI_B-PPPB2INFO3"; //!< UNI_B-PPPB2INFO3 message name +static constexpr uint16_t UNI_B_PPPB2INFO4_MSGID = 2308; //!< UNI_B-PPPB2INFO4 message ID +static constexpr const char* UNI_B_PPPB2INFO4_STRID = "UNI_B-PPPB2INFO4"; //!< UNI_B-PPPB2INFO4 message name +static constexpr uint16_t UNI_B_PPPB2INFO5_MSGID = 2310; //!< UNI_B-PPPB2INFO5 message ID +static constexpr const char* UNI_B_PPPB2INFO5_STRID = "UNI_B-PPPB2INFO5"; //!< UNI_B-PPPB2INFO5 message name +static constexpr uint16_t UNI_B_PPPB2INFO6_MSGID = 2312; //!< UNI_B-PPPB2INFO6 message ID +static constexpr const char* UNI_B_PPPB2INFO6_STRID = "UNI_B-PPPB2INFO6"; //!< UNI_B-PPPB2INFO6 message name +static constexpr uint16_t UNI_B_PPPB2INFO7_MSGID = 2314; //!< UNI_B-PPPB2INFO7 message ID +static constexpr const char* UNI_B_PPPB2INFO7_STRID = "UNI_B-PPPB2INFO7"; //!< UNI_B-PPPB2INFO7 message name +// @fp_codegen_end{FPSDK_COMMON_PARSER_UNIB_MESSAGES} +// clang-format on +///@} + +// --------------------------------------------------------------------------------------------------------------------- + +/** + * @brief UNI_B frame long header + */ +struct UnibHeader +{ // clang-format off + uint8_t sync1; //!< = UNI_B_SYNC_1 + uint8_t sync2; //!< = UNI_B_SYNC_2 + uint8_t sync3; //!< = UNI_B_SYNC_3_LONG + uint8_t cpu_idle; //!< CPU idle [%] (0-100), 1s average + uint16_t message_id; //!< Message ID + uint16_t message_size; //!< Size of message (payload?) TODO + uint8_t time_ref; //!< Time reference (UnibTimeRef) + uint8_t time_status; //!< Time status (UnibTimeStatus) + uint16_t wno; //!< Week number [-] + uint32_t tow_ms; //!< Time of week [ms] + uint32_t reserved; //!< Reserved + uint8_t version; //!< Unicore format version (TODO message (payload) version?) + uint8_t leap_sec; //!< Leap second (TODO number of leap seconds?) + uint16_t output_delay; //!< Output delay (w.r.t. measurement time) +}; // clang-format on + +static_assert(sizeof(UnibHeader) == UNI_B_HEAD_SIZE, ""); + +// --------------------------------------------------------------------------------------------------------------------- + +/** + * @brief Time reference + */ +enum class UnibTimeRef : uint8_t +{ // clang-format off + GPST = 0, //!< GPS + BDST = 1, //!< BeiDou +}; // clang-format on + +/** + * @brief Stringify time reference + * + * @param[in] time_ref The time reference + * + * @returns a unique string for the time reference + */ +const char* UnibTimeRefStr(const UnibTimeRef time_ref); + +/** + * @brief Time status + */ +enum class UnibTimeStatus : uint8_t +{ // clang-format off + UNKNOWN = static_cast(novb::NovbTimeStatus::UNKNOWN), //!< Unknown, precise time not known + FINE = static_cast(novb::NovbTimeStatus::FINE), //!< Precise time known +}; // clang-format on + +/** + * @brief Stringify time status + * + * @param[in] time_status The time status + * + * @returns a unique string for the time status + */ +const char* UnibTimeStatusStr(const UnibTimeStatus time_status); + +/** + * @brief Product model + */ +enum class UnibProductModel : uint32_t +{ // clang-format off + UNKNOWN = 0, //!< Unknown + UB4B0 = 1, //!< UB4B0 + UM4B0 = 2, //!< UM4B0 + UM480 = 3, //!< UM480 + UM440 = 4, //!< UM440 + UM482 = 5, //!< UM482 + UM442 = 6, //!< UM442 + UB482 = 7, //!< UB482 + UT4B0 = 8, //!< UT4B0 + UB362L = 10, //!< UB362L + UB4B0M = 11, //!< UB4B0M + UB4B0J = 12, //!< UB4B0J + UM482L = 13, //!< UM482L + UM4B0L = 14, //!< UM4B0L + CLAP_B = 16, //!< CLAP-B + UM982 = 17, //!< UM982 + UM980 = 18, //!< UM980 + UM960 = 19, //!< UM960 + UM980A = 21, //!< UM980A + CLAP_C = 23, //!< CLAP-C + UM960L = 24, //!< UM960L + UM981 = 26, //!< UM981 +}; // clang-format on + +/** + * @brief Stringify UNI_B-VERSION.product_model + * + * @param[in] model The model value + * + * @returns a short and unique string identifying the receiver model + */ +const char* UnibProductModelStr(const UnibProductModel model); + +// --------------------------------------------------------------------------------------------------------------------- + +/** + * @brief UNI_B-VERSION payload + */ +struct UnibVersionPayload +{ // clang-format off + uint32_t product_model; //!< Product model (UnibProductModel) + uint8_t firmware_version[33]; //!< Firmware version (nul-terminated string) + uint8_t auth_type[129]; //!< Authorization type (nul-terminated string) + uint8_t psn[66]; //!< PN and SN (nul-terminated string) + uint8_t board_id[33]; //!< Board ID (nul-terminated string) + uint8_t firmware_date[43]; //!< Firmware date (yyyy/mm/dd, nul-terminated string) +}; // clang-format on + +static_assert(sizeof(UnibVersionPayload) == 308, ""); + +/* ****************************************************************************************************************** */ +} // namespace unib +} // namespace parser +} // namespace common +} // namespace fpsdk +#endif // __FPSDK_COMMON_PARSER_UNIB_HPP__ diff --git a/fpsdk_common/include/fpsdk_common/stream/.gitkeep b/fpsdk_common/include/fpsdk_common/stream/.gitkeep deleted file mode 100644 index e69de29..0000000 diff --git a/fpsdk_common/include/fpsdk_common/string.hpp b/fpsdk_common/include/fpsdk_common/string.hpp index 9d7b4ca..9650910 100644 --- a/fpsdk_common/include/fpsdk_common/string.hpp +++ b/fpsdk_common/include/fpsdk_common/string.hpp @@ -354,6 +354,18 @@ std::string StrToUpper(const std::string& str); */ std::string StrToLower(const std::string& str); +/** + * @brief Stringify glibc error + * + * This works much like strerror(3), but is a bit more detailed adding the errnum value and name to the description. For + * example: StrError(EAGAIN) returns "Resource temporarily unavailable (11, EAGAIN)". + * + * @param[in] errnum The error number, see errno(3) + * + * @returns a string describing the error + */ +std::string StrError(const int errnum); + /* ****************************************************************************************************************** */ } // namespace string } // namespace common diff --git a/fpsdk_common/include/fpsdk_common/trafo.hpp b/fpsdk_common/include/fpsdk_common/trafo.hpp index 8f243c1..68bc2e2 100644 --- a/fpsdk_common/include/fpsdk_common/trafo.hpp +++ b/fpsdk_common/include/fpsdk_common/trafo.hpp @@ -47,8 +47,8 @@ static constexpr double WGS84_A = 6378137.0; //!< WGS-84 Earth static constexpr double WGS84_B = 6356752.314245; //!< WGS-84 Earth radius minor axis [m] static constexpr double WGS84_1F = 298.257223563; //!< WGS-84 1/f inverse of flattening parameter static constexpr double WGS84_E2 = 6.69437999014e-3; //!< WGS-84 first eccentricity squared -static constexpr double WGS84_A2 = WGS84_A * WGS84_A; //!< WGS-84 a_^2 -static constexpr double WGS84_B2 = WGS84_B * WGS84_B; //!< WGS-84 b_^2 +static constexpr double WGS84_A2 = WGS84_A * WGS84_A; //!< WGS-84 a^2 +static constexpr double WGS84_B2 = WGS84_B * WGS84_B; //!< WGS-84 b^2 static constexpr double WGS84_EE2 = WGS84_A2 / WGS84_B2 - 1; //!< WGS-84 e'^2 second eccentricity squared ///@} @@ -59,12 +59,16 @@ static constexpr double WGS84_EE2 = WGS84_A2 / WGS84_B2 - 1; //!< WGS-84 e'^2 s * @param[in] lon Reference longitude [rad] * * @returns the rotation matrix from ECEF to ENU + * + * Reference https://gssc.esa.int/navipedia/index.php/Transformations_between_ECEF_and_ENU_coordinates */ Eigen::Matrix3d RotEnuEcef(const double lat, const double lon); /** * @brief Calculate the rotation matrix from ECEF to ENU for a given reference position * + * @note The reference position is projected to the WGS84 ellipsoid + * * @param[in] ecef Reference position in ECEF [m] * * @returns the rotation matrix from ECEF to ENU @@ -74,9 +78,9 @@ Eigen::Matrix3d RotEnuEcef(const Eigen::Vector3d& ecef); /** * @brief Returns rotation matrix between NED and ENU * - * @details | 0, 1, 0 | - * | 1, 0, 0 | - * | 0, 0,-1 | + * | 0, 1, 0 | + * | 1, 0, 0 | + * | 0, 0, -1 | * * @returns the rotation matrix between NED and ENU */ @@ -93,10 +97,12 @@ Eigen::Matrix3d RotNedEnu(); Eigen::Matrix3d RotNedEcef(const double lat, const double lon); /** - * @brief Calculate the rotation matrix from ECEF to - * NED for a given reference origin. + * @brief Calculate the rotation matrix from ECEF to NED for a given reference origin + * + * @note The reference position is projected to the WGS84 ellipsoid * * @param[in] ecef Reference position in ECEF [m] + * * @returns the rRotation matrix from ECEF to NED */ Eigen::Matrix3d RotNedEcef(const Eigen::Vector3d& ecef); @@ -104,9 +110,8 @@ Eigen::Matrix3d RotNedEcef(const Eigen::Vector3d& ecef); /** * @brief Transform ECEF coordinate to ENU with specified ENU-origin * - * @param[in] ecef ECEF position to be transformed [m] - * - * @param[in] wgs84llh_ref ENU-origin in geodetic coordinates (lat [rad], lon [rad], height [m]) + * @param[in] ecef ECEF position to be transformed [m] + * @param[in] wgs84llh_ref ENU-origin in geodetic coordinates (lat [rad], lon [rad], height [m]) * * @returns the position in ENU coordinates */ @@ -142,13 +147,12 @@ Eigen::Vector3d TfEcefNed(const Eigen::Vector3d& ned, const Eigen::Vector3d& wgs * * @param[in] wgs84llh Geodetic coordinates (Lat[rad], Lon[rad], Height[m]) * - * @return Eigen::Vector3d ECEF coordinates [m] + * @returns the ECEF coordinates [m] */ Eigen::Vector3d TfEcefWgs84Llh(const Eigen::Vector3d& wgs84llh); /** * @brief Convert ECEF (x, y, z) coordinates to geodetic coordinates (latitude, longitude, height) - * (latitude, longitude, altitude). * * @param[in] ecef ECEF coordinates [m] * @@ -159,7 +163,7 @@ Eigen::Vector3d TfWgs84LlhEcef(const Eigen::Vector3d& ecef); /** * @brief Calculate yaw, pitch and roll in ENU from a given pose in ECEF * - * @details Yaw will be -Pi/2 when X is pointing North, because ENU starts with East + * Yaw is -Pi/2 when X points North, because ENU starts with East * * @param[in] ecef_p 3D position vector in ECEF * @param[in] ecef_r 3x3 rotation matrix representing rotation from body to ECEF @@ -169,7 +173,7 @@ Eigen::Vector3d TfWgs84LlhEcef(const Eigen::Vector3d& ecef); Eigen::Vector3d EcefPoseToEnuEul(const Eigen::Vector3d& ecef_p, const Eigen::Matrix3d& ecef_r); /** - * @brief Vector4 quaternion to intrinsic Euler Angles in ZYX (yaw,pitch,roll) + * @brief Vector4 quaternion to intrinsic Euler angles in ZYX (yaw, pitch, roll) * * @param[in] quat Quaternion (w, i, j, k) * @@ -178,26 +182,29 @@ Eigen::Vector3d EcefPoseToEnuEul(const Eigen::Vector3d& ecef_p, const Eigen::Mat Eigen::Vector3d QuatToEul(const Eigen::Quaterniond& quat); /** - * @brief Rotation Matrix to intrinsic Euler Angles in ZYX (Yaw-Pitch-Roll) order in radian + * @brief Rotation Matrix to intrinsic Euler angles in ZYX (yaw, pitch, roll) order in radian + * + * @param[in] rot Eigen::Matrix3d * - * @param rot Eigen::Matrix3d - * @return Eigen::Vector3d intrinsic euler angle in ZYX (Yaw-Pitch-Roll) order in radian + * @returns intrinsic euler angle in ZYX (Yaw-Pitch-Roll) order in radian */ Eigen::Vector3d RotToEul(const Eigen::Matrix3d& rot); /** * @brief Convert llh from deg to rad, height component unchanged * - * @param[in] llh_deg llh in degrees - * @return Eigen::Vector3d llh in radian + * @param[in] llh_deg llh in degrees + * + * @returns llh in radian */ Eigen::Vector3d LlhDegToRad(const Eigen::Vector3d& llh_deg); /** * @brief Convert llh from rad to deg, height component unchanged * - * @param[in] llh_rad llh in radian - * @return Eigen::Vector3d llh in degrees + * @param[in] llh_rad llh in radian + * + * @returns llh in degrees */ Eigen::Vector3d LlhRadToDeg(const Eigen::Vector3d& llh_rad); @@ -235,7 +242,7 @@ class Transformer /** * @brief Transform coordinates * - * @param[in,out] inout Coordinates to transform, will be replaced with result + * @param[in,out] inout Coordinates to transform, replaced with result * @param[in] inv Do the inverse transformation (true), default is forward (false) * * @returns true on success, false otherwise diff --git a/fpsdk_common/include/fpsdk_common/types.hpp b/fpsdk_common/include/fpsdk_common/types.hpp index be06cc2..21fe32e 100644 --- a/fpsdk_common/include/fpsdk_common/types.hpp +++ b/fpsdk_common/include/fpsdk_common/types.hpp @@ -48,33 +48,6 @@ constexpr typename std::underlying_type::type EnumToVal(T enum_val) return static_cast::type>(enum_val); } -/** - * @brief GNSS fix types - */ -enum class GnssFixType : int8_t // clang-format off -{ - FIX_UNKNOWN = 0, //!< Unknown fix - FIX_NOFIX = 1, //!< No fix - FIX_DRONLY = 2, //!< Dead-reckoning only fix - FIX_TIME = 3, //!< Time only fix - FIX_2D = 4, //!< 2D fix - FIX_3D = 5, //!< 3D fix - FIX_3D_DR = 6, //!< 3D + dead-reckoning fix - FIX_RTK_FLOAT = 7, //!< RTK float fix (implies 3D fix) - FIX_RTK_FIXED = 8, //!< RTK fixed fix (implies 3D fix) - FIX_RTK_FLOAT_DR = 9, //!< RTK float fix + dead-reckoning (implies 3D_DR fix) - FIX_RTK_FIXED_DR = 10, //!< RTK fixed fix + dead-reckoning (implies 3D_DR fix) -}; // clang-format on - -/** - * @brief Stringify GNSS fix type - * - * @param[in] fix_type The fix type - * - * @returns a concise and unique string for the fix types, "?" for bad values - */ -const char* GnssFixTypeStr(const GnssFixType fix_type); - /* ****************************************************************************************************************** */ } // namespace types } // namespace common diff --git a/fpsdk_common/src/codegen.pl b/fpsdk_common/src/codegen.pl new file mode 100755 index 0000000..4aca7a0 --- /dev/null +++ b/fpsdk_common/src/codegen.pl @@ -0,0 +1,812 @@ +#!/usr/bin/perl +# ___ ___ +# \ \ / / +# \ \/ / Copyright (c) Fixposition AG (www.fixposition.com) and contributors +# / /\ \ License: see the LICENSE file +# /__/ \__\ +# +# Fixposition SDK code generator +# +# You'll need: apt install libpath-tiny-perl libdigest-sha-perl +# +# Note that this is not run automatically at build time. Instead, you're supposed to run this manually and commit th +# modifed source files (and the changes to this script, obviously). +# +use strict; +use warnings; +use utf8; +use FindBin; +use Path::Tiny; +use Data::Dumper; +use Digest::SHA; + +######################################################################################################################## + +my @FPB_MESSAGES = +( + { name => 'GNSSSTATUS', msgid => 1201 }, + { name => 'SYSTEMSTATUS', msgid => 1301 }, + { name => 'MEASUREMENTS', msgid => 2001 }, + { name => 'VERSION', msgid => 2301 }, + { name => 'UNITTEST1', msgid => 65001 }, + { name => 'UNITTEST2', msgid => 65002 }, +); + +######################################################################################################################## + +my @NOVB_MESSAGES = +( + { name => 'BESTGNSSPOS', msgid => 1429 }, + { name => 'BESTPOS', msgid => 42 }, + { name => 'BESTUTM', msgid => 726 }, + { name => 'BESTVEL', msgid => 99 }, + { name => 'BESTXYZ', msgid => 241 }, + { name => 'CORRIMUS', msgid => 2264 }, + { name => 'HEADING2', msgid => 1335 }, + { name => 'IMURATECORRIMUS', msgid => 1362 }, + { name => 'INSCONFIG', msgid => 1945 }, + { name => 'INSPVA', msgid => 507 }, + { name => 'INSPVAS', msgid => 508 }, + { name => 'INSPVAX', msgid => 1465 }, + { name => 'INSSTDEV', msgid => 2051 }, + { name => 'PSRDOP2', msgid => 1163 }, + { name => 'RAWDMI', msgid => 2269 }, + { name => 'RAWIMU', msgid => 268 }, + { name => 'RAWIMUSX', msgid => 1462 }, + { name => 'RXSTATUS', msgid => 93 }, + { name => 'TIME', msgid => 101 }, +); + +######################################################################################################################## + +my @UNIB_MESSAGES = +( + { name => 'VERSION', msgid => 37 }, + { name => 'OBSVM', msgid => 12 }, + { name => 'OBSVH', msgid => 13 }, + { name => 'OBSVMCMP', msgid => 138 }, + { name => 'OBSVHCMP', msgid => 139 }, + { name => 'OBSVBASE', msgid => 284 }, + { name => 'BASEINFO', msgid => 176 }, + { name => 'GPSION', msgid => 8 }, + { name => 'BD3ION', msgid => 21 }, + { name => 'BDSION', msgid => 4 }, + { name => 'GALION', msgid => 9 }, + { name => 'GPSUTC', msgid => 19 }, + { name => 'BD3UTC', msgid => 22 }, + { name => 'BDSUTC', msgid => 2012 }, + { name => 'GALUTC', msgid => 20 }, + { name => 'GPSEPH', msgid => 106 }, + { name => 'QZSSEPH', msgid => 110 }, + { name => 'BD3EPH', msgid => 2999 }, + { name => 'BDSEPH', msgid => 108 }, + { name => 'GLOEPH', msgid => 107 }, + { name => 'GALEPH', msgid => 109 }, + { name => 'AGRIC', msgid => 1276 }, + { name => 'PVTSLN', msgid => 1021 }, + { name => 'BESTNAV', msgid => 2118 }, + { name => 'BESTNAVXYZ', msgid => 240 }, + { name => 'BESTNAVH', msgid => 2119 }, + { name => 'BESTNAVXYZH', msgid => 242 }, + { name => 'BESTSAT', msgid => 1041 }, + { name => 'ADRNAV', msgid => 142 }, + { name => 'ADRNAVH', msgid => 2117 }, + { name => 'PPPNAV', msgid => 1026 }, + { name => 'SPPNAV', msgid => 46 }, + { name => 'SPPNAVH', msgid => 2116 }, + { name => 'STADOP', msgid => 954 }, + { name => 'STADOPH', msgid => 2122 }, + { name => 'ADRDOP', msgid => 953 }, + { name => 'ADRDOPH', msgid => 2121 }, + { name => 'PPPDOP', msgid => 1025 }, + { name => 'SPPDOP', msgid => 173 }, + { name => 'SPPDOPH', msgid => 2120 }, + { name => 'SATSINFO', msgid => 2124 }, + { name => 'BASEPOS', msgid => 49 }, + { name => 'SATELLITE', msgid => 1042 }, + { name => 'SATECEF', msgid => 2115 }, + { name => 'RECTIME', msgid => 102 }, + { name => 'NOVHEADING', msgid => 972 }, + { name => 'NOVHEADING2', msgid => 1331 }, + { name => 'RTKSTATUS', msgid => 509 }, + { name => 'AGNSSSTATUS', msgid => 512 }, + { name => 'RTCSTATUS', msgid => 510 }, + { name => 'JAMSTATUS', msgid => 511 }, + { name => 'FREQJAMSTATUS', msgid => 519 }, + { name => 'RTCMSTATUS', msgid => 2125 }, + { name => 'HWSTATUS', msgid => 218 }, + { name => 'PPPSTATUS', msgid => 9000 }, + { name => 'AGC', msgid => 220 }, + { name => 'INFOPART1', msgid => 1019 }, + { name => 'INFOPART2', msgid => 1020 }, + { name => 'MSPOS', msgid => 520 }, + { name => 'TROPINFO', msgid => 2318 }, + { name => 'PTOBSINFO', msgid => 221 }, + { name => 'PPPB2INFO1', msgid => 2302 }, + { name => 'PPPB2INFO2', msgid => 2304 }, + { name => 'PPPB2INFO3', msgid => 2306 }, + { name => 'PPPB2INFO4', msgid => 2308 }, + { name => 'PPPB2INFO5', msgid => 2310 }, + { name => 'PPPB2INFO6', msgid => 2312 }, + { name => 'PPPB2INFO7', msgid => 2314 }, +); + +######################################################################################################################## + +my @UBX_CLASSES = +( + { name => 'ACK', clsid => 0x05 }, + { name => 'CFG', clsid => 0x06 }, + { name => 'ESF', clsid => 0x10 }, + { name => 'INF', clsid => 0x04 }, + { name => 'LOG', clsid => 0x21 }, + { name => 'MGA', clsid => 0x13 }, + { name => 'MON', clsid => 0x0a }, + { name => 'NAV', clsid => 0x01 }, + { name => 'NAV2', clsid => 0x29 }, + { name => 'RXM', clsid => 0x02 }, + { name => 'SEC', clsid => 0x27 }, + { name => 'TIM', clsid => 0x0d }, + { name => 'UPD', clsid => 0x09 }, + # fake classes + { name => 'NMEA', clsid => 0xf0 }, + { name => 'RTCM3', clsid => 0xf5 }, +); + +######################################################################################################################## + +my @UBX_MESSAGES = +( + { class => 'ACK', name => 'ACK', msgid => 0x01 }, + { class => 'ACK', name => 'NAK', msgid => 0x00 }, + { class => 'CFG', name => 'CFG', msgid => 0x09 }, + { class => 'CFG', name => 'PWR', msgid => 0x57 }, + { class => 'CFG', name => 'RST', msgid => 0x04 }, + { class => 'CFG', name => 'VALDEL', msgid => 0x8c }, + { class => 'CFG', name => 'VALGET', msgid => 0x8b }, + { class => 'CFG', name => 'VALSET', msgid => 0x8a }, + { class => 'ESF', name => 'ALG', msgid => 0x14 }, + { class => 'ESF', name => 'INS', msgid => 0x15 }, + { class => 'ESF', name => 'MEAS', msgid => 0x02 }, + { class => 'ESF', name => 'RAW', msgid => 0x03 }, + { class => 'ESF', name => 'STATUS', msgid => 0x10 }, + { class => 'INF', name => 'DEBUG', msgid => 0x04 }, + { class => 'INF', name => 'ERROR', msgid => 0x00 }, + { class => 'INF', name => 'NOTICE', msgid => 0x02 }, + { class => 'INF', name => 'TEST', msgid => 0x03 }, + { class => 'INF', name => 'WARNING', msgid => 0x01 }, + { class => 'LOG', name => 'CREATE', msgid => 0x07 }, + { class => 'LOG', name => 'ERASE', msgid => 0x03 }, + { class => 'LOG', name => 'FINDTIME', msgid => 0x0e }, + { class => 'LOG', name => 'INFO', msgid => 0x08 }, + { class => 'LOG', name => 'RETR', msgid => 0x09 }, + { class => 'LOG', name => 'RETRPOS', msgid => 0x0b }, + { class => 'LOG', name => 'RETRPOSX', msgid => 0x0f }, + { class => 'LOG', name => 'RETRSTR', msgid => 0x0d }, + { class => 'LOG', name => 'STR', msgid => 0x04 }, + { class => 'MGA', name => 'ACK', msgid => 0x60 }, + { class => 'MGA', name => 'BDS', msgid => 0x03 }, + { class => 'MGA', name => 'DBD', msgid => 0x80 }, + { class => 'MGA', name => 'GAL', msgid => 0x02 }, + { class => 'MGA', name => 'GLO', msgid => 0x06 }, + { class => 'MGA', name => 'GPS', msgid => 0x00 }, + { class => 'MGA', name => 'INI', msgid => 0x40 }, + { class => 'MGA', name => 'QZSS', msgid => 0x05 }, + { class => 'MON', name => 'COMMS', msgid => 0x36 }, + { class => 'MON', name => 'GNSS', msgid => 0x28 }, + { class => 'MON', name => 'HW', msgid => 0x09 }, + { class => 'MON', name => 'HW2', msgid => 0x0b }, + { class => 'MON', name => 'HW3', msgid => 0x37 }, + { class => 'MON', name => 'IO', msgid => 0x02 }, + { class => 'MON', name => 'MSGPP', msgid => 0x06 }, + { class => 'MON', name => 'PATCH', msgid => 0x27 }, + { class => 'MON', name => 'RF', msgid => 0x38 }, + { class => 'MON', name => 'RXBUF', msgid => 0x07 }, + { class => 'MON', name => 'RXR', msgid => 0x21 }, + { class => 'MON', name => 'SPAN', msgid => 0x31 }, + { class => 'MON', name => 'SYS', msgid => 0x39 }, + { class => 'MON', name => 'TEMP', msgid => 0x0e }, + { class => 'MON', name => 'TXBUF', msgid => 0x08 }, + { class => 'MON', name => 'VER', msgid => 0x04 }, + { class => 'NAV', name => 'ATT', msgid => 0x05 }, + { class => 'NAV', name => 'CLOCK', msgid => 0x22 }, + { class => 'NAV', name => 'COV', msgid => 0x36 }, + { class => 'NAV', name => 'DOP', msgid => 0x04 }, + { class => 'NAV', name => 'EELL', msgid => 0x3d }, + { class => 'NAV', name => 'EOE', msgid => 0x61 }, + { class => 'NAV', name => 'GEOFENCE', msgid => 0x39 }, + { class => 'NAV', name => 'HPPOSECEF', msgid => 0x13 }, + { class => 'NAV', name => 'HPPOSLLH', msgid => 0x14 }, + { class => 'NAV', name => 'ODO', msgid => 0x09 }, + { class => 'NAV', name => 'ORB', msgid => 0x34 }, + { class => 'NAV', name => 'PL', msgid => 0x62 }, + { class => 'NAV', name => 'POSECEF', msgid => 0x01 }, + { class => 'NAV', name => 'POSLLH', msgid => 0x02 }, + { class => 'NAV', name => 'PVAT', msgid => 0x17 }, + { class => 'NAV', name => 'PVT', msgid => 0x07 }, + { class => 'NAV', name => 'RELPOSNED', msgid => 0x3c }, + { class => 'NAV', name => 'RESETODO', msgid => 0x10 }, + { class => 'NAV', name => 'SAT', msgid => 0x35 }, + { class => 'NAV', name => 'SBAS', msgid => 0x32 }, + { class => 'NAV', name => 'SIG', msgid => 0x43 }, + { class => 'NAV', name => 'SLAS', msgid => 0x42 }, + { class => 'NAV', name => 'STATUS', msgid => 0x03 }, + { class => 'NAV', name => 'SVIN', msgid => 0x3b }, + { class => 'NAV', name => 'TIMEBDS', msgid => 0x24 }, + { class => 'NAV', name => 'TIMEGAL', msgid => 0x25 }, + { class => 'NAV', name => 'TIMEGLO', msgid => 0x23 }, + { class => 'NAV', name => 'TIMEGPS', msgid => 0x20 }, + { class => 'NAV', name => 'TIMELS', msgid => 0x26 }, + { class => 'NAV', name => 'TIMEQZSS', msgid => 0x27 }, + { class => 'NAV', name => 'TIMETRUSTED', msgid => 0x64 }, + { class => 'NAV', name => 'TIMEUTC', msgid => 0x21 }, + { class => 'NAV', name => 'VELECEF', msgid => 0x11 }, + { class => 'NAV', name => 'VELNED', msgid => 0x12 }, + { class => 'NAV2', name => 'CLOCK', msgid => "UBX_NAV_CLOCK_MSGID" }, + { class => 'NAV2', name => 'COV', msgid => "UBX_NAV_COV_MSGID" }, + { class => 'NAV2', name => 'DOP', msgid => "UBX_NAV_DOP_MSGID" }, + { class => 'NAV2', name => 'EOE', msgid => "UBX_NAV_EOE_MSGID" }, + { class => 'NAV2', name => 'ODO', msgid => "UBX_NAV_ODO_MSGID" }, + { class => 'NAV2', name => 'POSECEF', msgid => "UBX_NAV_POSECEF_MSGID" }, + { class => 'NAV2', name => 'POSLLH', msgid => "UBX_NAV_POSLLH_MSGID" }, + { class => 'NAV2', name => 'PVT', msgid => "UBX_NAV_PVT_MSGID" }, + { class => 'NAV2', name => 'SAT', msgid => "UBX_NAV_SAT_MSGID" }, + { class => 'NAV2', name => 'SBAS', msgid => "UBX_NAV_SBAS_MSGID" }, + { class => 'NAV2', name => 'SIG', msgid => "UBX_NAV_SIG_MSGID" }, + { class => 'NAV2', name => 'SLAS', msgid => "UBX_NAV_SLAS_MSGID" }, + { class => 'NAV2', name => 'STATUS', msgid => "UBX_NAV_STATUS_MSGID" }, + { class => 'NAV2', name => 'SVIN', msgid => "UBX_NAV_SVIN_MSGID" }, + { class => 'NAV2', name => 'TIMEBDS', msgid => "UBX_NAV_TIMEBDS_MSGID" }, + { class => 'NAV2', name => 'TIMEGAL', msgid => "UBX_NAV_TIMEGAL_MSGID" }, + { class => 'NAV2', name => 'TIMEGLO', msgid => "UBX_NAV_TIMEGLO_MSGID" }, + { class => 'NAV2', name => 'TIMEGPS', msgid => "UBX_NAV_TIMEGPS_MSGID" }, + { class => 'NAV2', name => 'TIMELS', msgid => "UBX_NAV_TIMELS_MSGID" }, + { class => 'NAV2', name => 'TIMEQZSS', msgid => "UBX_NAV_TIMEQZSS_MSGID" }, + { class => 'NAV2', name => 'TIMEUTC', msgid => "UBX_NAV_TIMEUTC_MSGID" }, + { class => 'NAV2', name => 'VELECEF', msgid => "UBX_NAV_VELECEF_MSGID" }, + { class => 'NAV2', name => 'VELNED', msgid => "UBX_NAV_VELNED_MSGID" }, + { class => 'RXM', name => 'COR', msgid => 0x14 }, + { class => 'RXM', name => 'MEASX', msgid => 0x14 }, + { class => 'RXM', name => 'PMP', msgid => 0x72 }, + { class => 'RXM', name => 'PMREQ', msgid => 0x41 }, + { class => 'RXM', name => 'QZSSL6', msgid => 0x73 }, + { class => 'RXM', name => 'RAWX', msgid => 0x15 }, + { class => 'RXM', name => 'RLM', msgid => 0x59 }, + { class => 'RXM', name => 'RTCM', msgid => 0x32 }, + { class => 'RXM', name => 'SFRBX', msgid => 0x13 }, + { class => 'RXM', name => 'SPARTN', msgid => 0x33 }, + { class => 'RXM', name => 'SPARTNKEY', msgid => 0x36 }, + { class => 'SEC', name => 'OSNMA', msgid => 0x0a }, + { class => 'SEC', name => 'SIG', msgid => 0x09 }, + { class => 'SEC', name => 'SIGLOG', msgid => 0x10 }, + { class => 'SEC', name => 'UNIQID', msgid => 0x03 }, + { class => 'TIM', name => 'TM2', msgid => 0x03 }, + { class => 'TIM', name => 'TP', msgid => 0x01 }, + { class => 'TIM', name => 'VRFY', msgid => 0x06 }, + { class => 'UPD', name => 'FLDET', msgid => 0x08 }, + { class => 'UPD', name => 'POS', msgid => 0x15 }, + { class => 'UPD', name => 'SAFEBOOT', msgid => 0x07 }, + { class => 'UPD', name => 'SOS', msgid => 0x14 }, + # fake classes + { class => 'NMEA', name => 'STANDARD_DTM', msgid => 0x0a }, + { class => 'NMEA', name => 'STANDARD_GAQ', msgid => 0x45 }, + { class => 'NMEA', name => 'STANDARD_GBQ', msgid => 0x44 }, + { class => 'NMEA', name => 'STANDARD_GBS', msgid => 0x09 }, + { class => 'NMEA', name => 'STANDARD_GGA', msgid => 0x00 }, + { class => 'NMEA', name => 'STANDARD_GLL', msgid => 0x01 }, + { class => 'NMEA', name => 'STANDARD_GLQ', msgid => 0x43 }, + { class => 'NMEA', name => 'STANDARD_GNQ', msgid => 0x42 }, + { class => 'NMEA', name => 'STANDARD_GNS', msgid => 0x0d }, + { class => 'NMEA', name => 'STANDARD_GPQ', msgid => 0x40 }, + { class => 'NMEA', name => 'STANDARD_GQQ', msgid => 0x47 }, + { class => 'NMEA', name => 'STANDARD_GRS', msgid => 0x06 }, + { class => 'NMEA', name => 'STANDARD_GSA', msgid => 0x02 }, + { class => 'NMEA', name => 'STANDARD_GST', msgid => 0x07 }, + { class => 'NMEA', name => 'STANDARD_GSV', msgid => 0x03 }, + { class => 'NMEA', name => 'STANDARD_RLM', msgid => 0x0b }, + { class => 'NMEA', name => 'STANDARD_RMC', msgid => 0x04 }, + { class => 'NMEA', name => 'STANDARD_TXT', msgid => 0x41 }, + { class => 'NMEA', name => 'STANDARD_VLW', msgid => 0x0f }, + { class => 'NMEA', name => 'STANDARD_VTG', msgid => 0x05 }, + { class => 'NMEA', name => 'STANDARD_ZDA', msgid => 0x08 }, + { class => 'NMEA', name => 'PUBX_CONFIG', msgid => 0x41 }, + { class => 'NMEA', name => 'PUBX_POSITION', msgid => 0x00 }, + { class => 'NMEA', name => 'PUBX_RATE', msgid => 0x40 }, + { class => 'NMEA', name => 'PUBX_SVSTATUS', msgid => 0x03 }, + { class => 'NMEA', name => 'PUBX_TIME', msgid => 0x04 }, + { class => 'RTCM3', name => 'TYPE1001', msgid => 0x01 }, + { class => 'RTCM3', name => 'TYPE1002', msgid => 0x02 }, + { class => 'RTCM3', name => 'TYPE1003', msgid => 0x03 }, + { class => 'RTCM3', name => 'TYPE1004', msgid => 0x04 }, + { class => 'RTCM3', name => 'TYPE1005', msgid => 0x05 }, + { class => 'RTCM3', name => 'TYPE1006', msgid => 0x06 }, + { class => 'RTCM3', name => 'TYPE1007', msgid => 0x07 }, + { class => 'RTCM3', name => 'TYPE1009', msgid => 0x09 }, + { class => 'RTCM3', name => 'TYPE1010', msgid => 0x0a }, + { class => 'RTCM3', name => 'TYPE1011', msgid => 0xa1 }, + { class => 'RTCM3', name => 'TYPE1012', msgid => 0xa2 }, + { class => 'RTCM3', name => 'TYPE1033', msgid => 0x21 }, + { class => 'RTCM3', name => 'TYPE1074', msgid => 0x4a }, + { class => 'RTCM3', name => 'TYPE1075', msgid => 0x4b }, + { class => 'RTCM3', name => 'TYPE1077', msgid => 0x4d }, + { class => 'RTCM3', name => 'TYPE1084', msgid => 0x54 }, + { class => 'RTCM3', name => 'TYPE1085', msgid => 0x55 }, + { class => 'RTCM3', name => 'TYPE1087', msgid => 0x57 }, + { class => 'RTCM3', name => 'TYPE1094', msgid => 0x5e }, + { class => 'RTCM3', name => 'TYPE1095', msgid => 0x5f }, + { class => 'RTCM3', name => 'TYPE1097', msgid => 0x61 }, + { class => 'RTCM3', name => 'TYPE1124', msgid => 0x7c }, + { class => 'RTCM3', name => 'TYPE1125', msgid => 0x7d }, + { class => 'RTCM3', name => 'TYPE1127', msgid => 0x7f }, + { class => 'RTCM3', name => 'TYPE1230', msgid => 0xe6 }, + { class => 'RTCM3', name => 'TYPE4072_0', msgid => 0xfe }, + { class => 'RTCM3', name => 'TYPE4072_1', msgid => 0xfd }, +); + +######################################################################################################################## + +my @RTCM3_MESSAGES = +( + { type => 1001, desc => "L1-only GPS RTK observables" }, + { type => 1002, desc => "Extended L1-only GPS RTK observables" }, + { type => 1003, desc => "L1/L2 GPS RTK observables" }, + { type => 1004, desc => "Extended L1/L2 GPS RTK observables" }, + { type => 1005, desc => "Stationary RTK reference station ARP" }, + { type => 1006, desc => "Stationary RTK reference station ARP with antenna height" }, + { type => 1007, desc => "Antenna descriptor" }, + { type => 1008, desc => "Antenna descriptor and serial number" }, + { type => 1009, desc => "L1-only GLONASS RTK observables" }, + { type => 1010, desc => "Extended L1-only GLONASS RTK observables" }, + { type => 1011, desc => "L1/L2 GLONASS RTK observables" }, + { type => 1012, desc => "Extended L1/L2 GLONASS RTK observables" }, + # + { type => 1030, desc => "GPS network RTK residual message" }, + { type => 1031, desc => "GLONASS network RTK residual message" }, + { type => 1032, desc => "Physical reference station position message" }, + { type => 1033, desc => "Receiver and antenna descriptors" }, + { type => 1230, desc => "GLONASS code-phase biases" }, + # + { type => 1071, desc => "GPS MSM1 (C)" }, + { type => 1072, desc => "GPS MSM2 (L)" }, + { type => 1073, desc => "GPS MSM3 (C, L)" }, + { type => 1074, desc => "GPS MSM4 (full C, full L, S)" }, + { type => 1075, desc => "GPS MSM5 (full C, full L, S, D)" }, + { type => 1076, desc => "GPS MSM6 (ext full C, ext full L, S)" }, + { type => 1077, desc => "GPS MSM7 (ext full C, ext full L, S, D)" }, + { type => 1081, desc => "GLONASS MSM1 (C)" }, + { type => 1082, desc => "GLONASS MSM2 (L)" }, + { type => 1083, desc => "GLONASS MSM3 (C, L)" }, + { type => 1084, desc => "GLONASS MSM4 (full C, full L, S)" }, + { type => 1085, desc => "GLONASS MSM5 (full C, full L, S, D)" }, + { type => 1086, desc => "GLONASS MSM6 (ext full C, ext full L, S)" }, + { type => 1087, desc => "GLONASS MSM7 (ext full C, ext full L, S, D)" }, + { type => 1091, desc => "Galileo MSM1 (C)" }, + { type => 1092, desc => "Galileo MSM2 (L)" }, + { type => 1093, desc => "Galileo MSM3 (C, L)" }, + { type => 1094, desc => "Galileo MSM4 (full C, full L, S)" }, + { type => 1095, desc => "Galileo MSM5 (full C, full L, S, D)" }, + { type => 1096, desc => "Galileo MSM6 (full C, full L, S)" }, + { type => 1097, desc => "Galileo MSM7 (ext full C, ext full L, S, D)" }, + { type => 1101, desc => "SBAS MSM1 (C)" }, + { type => 1102, desc => "SBAS MSM2 (L)" }, + { type => 1103, desc => "SBAS MSM3 (C, L)" }, + { type => 1104, desc => "SBAS MSM4 (full C, full L, S)" }, + { type => 1105, desc => "SBAS MSM5 (full C, full L, S, D)" }, + { type => 1106, desc => "SBAS MSM6 (full C, full L, S)" }, + { type => 1107, desc => "SBAS MSM7 (ext full C, ext full L, S, D)" }, + { type => 1111, desc => "QZSS MSM1 (C)" }, + { type => 1112, desc => "QZSS MSM2 (L)" }, + { type => 1113, desc => "QZSS MSM3 (C, L)" }, + { type => 1114, desc => "QZSS MSM4 (full C, full L, S)" }, + { type => 1115, desc => "QZSS MSM5 (full C, full L, S, D)" }, + { type => 1116, desc => "QZSS MSM6 (full C, full L, S)" }, + { type => 1117, desc => "QZSS MSM7 (ext full C, ext full L, S, D)" }, + { type => 1121, desc => "BeiDou MSM1 (C)" }, + { type => 1122, desc => "BeiDou MSM2 (L)" }, + { type => 1123, desc => "BeiDou MSM3 (C, L)" }, + { type => 1124, desc => "BeiDou MSM4 (full C, full L, S)" }, + { type => 1125, desc => "BeiDou MSM5 (full C, full L, S, D)" }, + { type => 1126, desc => "BeiDou MSM6 (full C, full L, S)" }, + { type => 1127, desc => "BeiDou MSM7 (ext full C, ext full L, S, D)" }, + { type => 1131, desc => "NavIC MSM1 (C)" }, + { type => 1132, desc => "NavIC MSM2 (L)" }, + { type => 1133, desc => "NavIC MSM3 (C, L)" }, + { type => 1134, desc => "NavIC MSM4 (full C, full L, S)" }, + { type => 1135, desc => "NavIC MSM5 (full C, full L, S, D)" }, + { type => 1136, desc => "NavIC MSM6 (full C, full L, S)" }, + { type => 1137, desc => "NavIC MSM7 (ext full C, ext full L, S, D)" }, + # + { type => 1019, desc => "GPS ephemerides" }, + { type => 1020, desc => "GLONASS ephemerides" }, + { type => 1042, desc => "BeiDou satellite ephemeris data" }, + { type => 1044, desc => "QZSS ephemerides" }, + { type => 1045, desc => "Galileo F/NAV satellite ephemeris data" }, + { type => 1046, desc => "Galileo I/NAV satellite ephemeris data" }, + # + { type => 4050, desc => "STMicroelectronics proprietary" }, + { type => 4051, desc => "Hi-Target proprietary" }, + { type => 4052, desc => "Furuno proprietary" }, + { type => 4053, desc => "Qualcomm proprietary" }, + { type => 4054, desc => "Geodnet proprietary" }, + { type => 4055, desc => "KRISO proprietary" }, + { type => 4056, desc => "Dayou proprietary" }, + { type => 4057, desc => "Sixents proprietary" }, + { type => 4058, desc => "Anello proprietary" }, + { type => 4059, desc => "NRCan proprietary" }, + { type => 4060, desc => "ALES proprietary" }, + { type => 4061, desc => "Geely proprietary" }, + { type => 4062, desc => "SwiftNav proprietary" }, + { type => 4063, desc => "CHCNAV proprietary" }, + { type => 4064, desc => "NTLab proprietary" }, + { type => 4065, desc => "Allystar proprietary" }, + { type => 4066, desc => "Lantmateriet proprietary" }, + { type => 4067, desc => "CIPPE proprietary" }, + { type => 4068, desc => "Qianxun proprietary" }, + { type => 4069, desc => "Veripos proprietary" }, + { type => 4070, desc => "Wuhan MengXin proprietary" }, + { type => 4071, desc => "Wuhan Navigation proprietary" }, + { type => 4072, desc => "u-blox proprietary", }, + { type => 4073, desc => "Mitsubishi proprietary" }, + { type => 4074, desc => "Unicore proprietary" }, + { type => 4075, desc => "Alberding proprietary" }, + { type => 4076, desc => "IGS proprietary" }, + { type => 4077, desc => "Hemisphere proprietary" }, + { type => 4078, desc => "ComNav proprietary" }, + { type => 4079, desc => "SubCarrier proprietary" }, + { type => 4080, desc => "NavCom proprietary" }, + { type => 4081, desc => "SNU GNSS proprietary" }, + { type => 4082, desc => "CRCSI proprietary" }, + { type => 4083, desc => "DLR proprietary" }, + { type => 4084, desc => "Geodetics, Inc proprietary" }, + { type => 4085, desc => "EUSPA proprietary" }, + { type => 4086, desc => "inPosition proprietary" }, + { type => 4087, desc => "Fugro proprietary" }, + { type => 4088, desc => "IfEN proprietary" }, + { type => 4089, desc => "Septentrio proprietary" }, + { type => 4090, desc => "Geo++ proprietary" }, + { type => 4091, desc => "Topcon proprietary" }, + { type => 4092, desc => "Leica proprietary" }, + { type => 4093, desc => "NovAtel proprietary" }, + { type => 4094, desc => "Trimble proprietary" }, + { type => 4095, desc => "Ashtech proprietary" }, +); + +my @RTCM3_SUBTYPES = +( + { type => 4072, subtype => 0, desc => "u-blox proprietary: Reference station PVT" }, + { type => 4072, subtype => 1, desc => "u-blox proprietary: Additional reference station information" }, +); + +######################################################################################################################## + +my @SPARTN_MESSAGES = +( + { name => 'OCB', type => 0, desc => 'Orbits, clock, bias (OCB)' }, + { name => 'HPAC', type => 1, desc => 'High-precision atmosphere correction (HPAC)' }, + { name => 'GAD', type => 2, desc => 'Geographic area definition (GAD)' }, + { name => 'BPAC', type => 3, desc => 'Basic-precision atmosphere correction (BPAC)' }, + { name => 'EAS', type => 4, desc => 'Encryption and authentication support (EAS)' }, + { name => 'PROP', type => 120, desc => 'Proprietary message' }, +); + +my @SPARTN_SUBTYPES = +( + { type => 'OCB', name => 'GPS', subtype => 0, desc => 'Orbits, clock, bias (OCB) GPS' }, + { type => 'OCB', name => 'GLO', subtype => 1, desc => 'Orbits, clock, bias (OCB) GLONASS' }, + { type => 'OCB', name => 'GAL', subtype => 2, desc => 'Orbits, clock, bias (OCB) Galileo' }, + { type => 'OCB', name => 'BDS', subtype => 3, desc => 'Orbits, clock, bias (OCB) BeiDou' }, + { type => 'OCB', name => 'QZSS', subtype => 4, desc => 'Orbits, clock, bias (OCB) QZSS' }, + { type => 'HPAC', name => 'GPS', subtype => 0, desc => 'High-precision atmosphere correction (HPAC) GPS' }, + { type => 'HPAC', name => 'GLO', subtype => 1, desc => 'High-precision atmosphere correction (HPAC) GLONASS' }, + { type => 'HPAC', name => 'GAL', subtype => 2, desc => 'High-precision atmosphere correction (HPAC) Galileo' }, + { type => 'HPAC', name => 'BDS', subtype => 3, desc => 'High-precision atmosphere correction (HPAC) BeiDou' }, + { type => 'HPAC', name => 'QZSS', subtype => 4, desc => 'High-precision atmosphere correction (HPAC) QZSS' }, + { type => 'GAD', name => 'GAD', subtype => 0, desc => 'Geographic area definition (GAD)' }, + { type => 'BPAC', name => 'POLY', subtype => 0, desc => 'Basic-precision atmosphere correction (BPAC)' }, + { type => 'EAS', name => 'KEY', subtype => 0, desc => 'Encryption and authentication support (EAS): Dynamic key' }, + { type => 'EAS', name => 'GROUP', subtype => 1, desc => 'Encryption and authentication support (EAS): Group authentication' }, + { type => 'PROP', name => 'EST', subtype => 0, desc => 'Proprietary messages: test' }, + { type => 'PROP', name => 'UBLOX', subtype => 1, desc => 'Proprietary messages: u-blox' }, + { type => 'PROP', name => 'SWIFT', subtype => 2, desc => 'Proprietary messages: Swift' }, +); + +######################################################################################################################## + +my $FPSDK_COMMON_DIR = path("$FindBin::Bin/..")->canonpath(); +my @CODEGEN_FILES = (); +my %CODEGEN_SECTIONS = (); + +######################################################################################################################## +# Generate code for FP_B +do +{ + push(@CODEGEN_FILES, + path("$FPSDK_COMMON_DIR/include/fpsdk_common/parser/fpb.hpp"), + path("$FPSDK_COMMON_DIR/src/parser/fpb.cpp")); + $CODEGEN_SECTIONS{FPSDK_COMMON_PARSER_FPB_MESSAGES} = []; + $CODEGEN_SECTIONS{FPSDK_COMMON_PARSER_FPB_MSGINFO} = + [ + "static constexpr std::array MSG_INFO =\n", + "{{\n", + ]; + foreach my $entry (@FPB_MESSAGES) + { + my $name = "FP_B-$entry->{name}"; + my $msgid = "FP_B_$entry->{name}_MSGID"; + my $strid = "FP_B_$entry->{name}_STRID"; + push(@{$CODEGEN_SECTIONS{FPSDK_COMMON_PARSER_FPB_MESSAGES}}, + sprintf("static constexpr uint16_t %-30s = %5d; //!< $name message ID\n", $msgid, $entry->{msgid}), + sprintf("static constexpr const char* %-30s = %-25s //!< $name message name\n", $strid, "\"${name}\";"), + ); + push(@{$CODEGEN_SECTIONS{FPSDK_COMMON_PARSER_FPB_MSGINFO}}, + sprintf(" { %-30s %-30s },\n", "$msgid,", $strid), + ); + } + push(@{$CODEGEN_SECTIONS{FPSDK_COMMON_PARSER_FPB_MSGINFO}}, + "}};\n"); +}; + +######################################################################################################################## +# Generate code for NOV_B +do +{ + push(@CODEGEN_FILES, + path("$FPSDK_COMMON_DIR/include/fpsdk_common/parser/novb.hpp"), + path("$FPSDK_COMMON_DIR/src/parser/novb.cpp")); + $CODEGEN_SECTIONS{FPSDK_COMMON_PARSER_NOVB_MESSAGES} = []; + $CODEGEN_SECTIONS{FPSDK_COMMON_PARSER_NOVB_MSGINFO} = + [ + "static constexpr std::array MSG_INFO =\n", + "{{\n", + ]; + foreach my $entry (@NOVB_MESSAGES) + { + my $name = "NOV_B-$entry->{name}"; + my $msgid = "NOV_B_$entry->{name}_MSGID"; + my $strid = "NOV_B_$entry->{name}_STRID"; + push(@{$CODEGEN_SECTIONS{FPSDK_COMMON_PARSER_NOVB_MESSAGES}}, + sprintf("static constexpr uint16_t %-30s = %5d; //!< $name message ID\n", $msgid, $entry->{msgid}), + sprintf("static constexpr const char* %-30s = %-25s //!< $name message name\n", $strid, "\"${name}\";"), + ); + push(@{$CODEGEN_SECTIONS{FPSDK_COMMON_PARSER_NOVB_MSGINFO}}, + sprintf(" { %-30s %-30s },\n", "$msgid,", $strid), + ); + } + push(@{$CODEGEN_SECTIONS{FPSDK_COMMON_PARSER_NOVB_MSGINFO}}, + "}};\n"); +}; + +######################################################################################################################## +# Generate code for UNI_B +do +{ + push(@CODEGEN_FILES, + path("$FPSDK_COMMON_DIR/include/fpsdk_common/parser/unib.hpp"), + path("$FPSDK_COMMON_DIR/src/parser/unib.cpp")); + $CODEGEN_SECTIONS{FPSDK_COMMON_PARSER_UNIB_MESSAGES} = []; + $CODEGEN_SECTIONS{FPSDK_COMMON_PARSER_UNIB_MSGINFO} = + [ + "static constexpr std::array MSG_INFO =\n", + "{{\n", + ]; + foreach my $entry (@UNIB_MESSAGES) + { + my $name = "UNI_B-$entry->{name}"; + my $msgid = "UNI_B_$entry->{name}_MSGID"; + my $strid = "UNI_B_$entry->{name}_STRID"; + push(@{$CODEGEN_SECTIONS{FPSDK_COMMON_PARSER_UNIB_MESSAGES}}, + sprintf("static constexpr uint16_t %-30s = %5d; //!< $name message ID\n", $msgid, $entry->{msgid}), + sprintf("static constexpr const char* %-30s = %-25s //!< $name message name\n", $strid, "\"${name}\";"), + ); + push(@{$CODEGEN_SECTIONS{FPSDK_COMMON_PARSER_UNIB_MSGINFO}}, + sprintf(" { %-30s %-30s },\n", "$msgid,", $strid), + ); + } + push(@{$CODEGEN_SECTIONS{FPSDK_COMMON_PARSER_UNIB_MSGINFO}}, + "}};\n"); +}; + + +######################################################################################################################## +# Generate code for UBX +do +{ + push(@CODEGEN_FILES, + path("$FPSDK_COMMON_DIR/include/fpsdk_common/parser/ubx.hpp"), + path("$FPSDK_COMMON_DIR/src/parser/ubx.cpp")); + $CODEGEN_SECTIONS{FPSDK_COMMON_PARSER_UBX_CLASSES} = []; + $CODEGEN_SECTIONS{FPSDK_COMMON_PARSER_UBX_MSGINFO_CPP} = [ + "static const UbxClassesInfo CLS_INFO =\n", + "{{\n", + ]; + foreach my $entry (@UBX_CLASSES) + { + my $name = "UBX-$entry->{name}"; + my $clsid = "UBX_$entry->{name}_CLSID"; + my $strid = "UBX_$entry->{name}_STRID"; + # print(Dumper($entry);) + push(@{$CODEGEN_SECTIONS{FPSDK_COMMON_PARSER_UBX_CLASSES}}, + sprintf("static constexpr uint16_t %-30s = 0x%02x; //!< $name class ID\n", $clsid, $entry->{clsid}), + sprintf("static constexpr const char* %-30s = %-25s //!< $name class name\n", $strid, "\"${name}\";"), + ); + push(@{$CODEGEN_SECTIONS{FPSDK_COMMON_PARSER_UBX_MSGINFO_CPP}}, + sprintf(" { %-30s 0x00, %-30s },\n", "$clsid,", $strid), + ); + } + push(@{$CODEGEN_SECTIONS{FPSDK_COMMON_PARSER_UBX_MSGINFO_CPP}}, + "}};\n", + ); + + $CODEGEN_SECTIONS{FPSDK_COMMON_PARSER_UBX_MESSAGES} = []; + $CODEGEN_SECTIONS{FPSDK_COMMON_PARSER_UBX_MSGINFO_HPP} = [ + "using UbxClassesInfo = std::array; //!< UBX classes lookup table\n", + "using UbxMessagesInfo = std::array; //!< UBX messages lookup table\n", + ]; + push(@{$CODEGEN_SECTIONS{FPSDK_COMMON_PARSER_UBX_MSGINFO_CPP}}, + "static const UbxMessagesInfo MSG_INFO =\n", + "{{\n", + ); + foreach my $entry (@UBX_MESSAGES) + { + my $name = "UBX-$entry->{class}-$entry->{name}"; + my $clsid = "UBX_$entry->{class}_CLSID"; + my $msgid = "UBX_$entry->{class}_$entry->{name}_MSGID"; + my $strid = "UBX_$entry->{class}_$entry->{name}_STRID"; + push(@{$CODEGEN_SECTIONS{FPSDK_COMMON_PARSER_UBX_MESSAGES}}, + ($entry->{msgid} =~ m{^UBX} ? + sprintf("static constexpr uint16_t %-30s = %-24s //!< $name message ID\n", $msgid, "$entry->{msgid};") : + sprintf("static constexpr uint16_t %-30s = 0x%02x; //!< $name message ID\n", $msgid, $entry->{msgid}) + ), + sprintf("static constexpr const char* %-30s = %-25s //!< $name message name\n", "UBX_$entry->{class}_$entry->{name}_STRID", "\"${name}\";"), + ); + push(@{$CODEGEN_SECTIONS{FPSDK_COMMON_PARSER_UBX_MSGINFO_CPP}}, + sprintf(" { %-30s %-30s %-30s },\n", "$clsid,", "$msgid,", $strid), + ); + } + push(@{$CODEGEN_SECTIONS{FPSDK_COMMON_PARSER_UBX_MSGINFO_CPP}}, + "}};\n", + ); +}; + + +######################################################################################################################## +# Generate code for RTCM3 +do +{ + push(@CODEGEN_FILES, + path("$FPSDK_COMMON_DIR/include/fpsdk_common/parser/rtcm3.hpp"), + path("$FPSDK_COMMON_DIR/src/parser/rtcm3.cpp")); + $CODEGEN_SECTIONS{FPSDK_COMMON_PARSER_RTCM3_MESSAGES} = []; + $CODEGEN_SECTIONS{FPSDK_COMMON_PARSER_RTCM3_MSGINFO} = + [ + "static constexpr std::array MSG_INFO =\n", + "{{\n", + ]; + foreach my $entry (@RTCM3_MESSAGES) + { + my $type = sprintf("TYPE%04d", $entry->{type}); + my $name = "RTCM3-${type}"; + my $msgid = "RTCM3_${type}_MSGID"; + my $strid = "RTCM3_${type}_STRID"; + push(@{$CODEGEN_SECTIONS{FPSDK_COMMON_PARSER_RTCM3_MESSAGES}}, + sprintf("static constexpr uint16_t %-30s = %4d; //!< $name message ID\n", $msgid, $entry->{type}), + sprintf("static constexpr const char* %-30s = %-25s //!< $name message name\n", $strid, "\"${name}\";"), + ); + push(@{$CODEGEN_SECTIONS{FPSDK_COMMON_PARSER_RTCM3_MSGINFO}}, + sprintf(" { %s, 0, %s, \"%s\" },\n", $msgid, $strid, $entry->{desc}), + ); + } + push(@{$CODEGEN_SECTIONS{FPSDK_COMMON_PARSER_RTCM3_MSGINFO}}, + "}};\n", + "static constexpr std::array SUB_INFO =\n", + "{{\n"); + foreach my $entry (@RTCM3_SUBTYPES) + { + my $type = sprintf("TYPE%04d", $entry->{type}); + my $name = "RTCM3-${type}_$entry->{subtype}"; + my $msgid = "RTCM3_${type}_MSGID"; + my $subid = "RTCM3_${type}_$entry->{subtype}_SUBID"; + my $strid = "RTCM3_${type}_$entry->{subtype}_STRID"; + push(@{$CODEGEN_SECTIONS{FPSDK_COMMON_PARSER_RTCM3_MESSAGES}}, + sprintf("static constexpr uint16_t %-30s = %d; //!< $name message ID\n", $subid, $entry->{subtype}), + sprintf("static constexpr const char* %-30s = %-25s //!< $name message name\n", $strid, "\"${name}\";"), + ); + push(@{$CODEGEN_SECTIONS{FPSDK_COMMON_PARSER_RTCM3_MSGINFO}}, + sprintf(" { %s, %s, %s, \"%s\" },\n", $msgid, $subid, $strid, $entry->{desc}), + ); + } + push(@{$CODEGEN_SECTIONS{FPSDK_COMMON_PARSER_RTCM3_MSGINFO}}, + "}};\n"); +}; + +######################################################################################################################## +# Generate code for SPARTN +do +{ + push(@CODEGEN_FILES, + path("$FPSDK_COMMON_DIR/include/fpsdk_common/parser/spartn.hpp"), + path("$FPSDK_COMMON_DIR/src/parser/spartn.cpp")); + $CODEGEN_SECTIONS{FPSDK_COMMON_PARSER_SPARTN_MESSAGES} = []; + $CODEGEN_SECTIONS{FPSDK_COMMON_PARSER_SPARTN_MSGINFO} = + [ + "static constexpr std::array MSG_INFO =\n", + "{{\n", + ]; + foreach my $entry (@SPARTN_MESSAGES) + { + my $name = "SPARTN-$entry->{name}"; + my $msgid = "SPARTN_$entry->{name}_MSGID"; + my $strid = "SPARTN_$entry->{name}_STRID"; + push(@{$CODEGEN_SECTIONS{FPSDK_COMMON_PARSER_SPARTN_MESSAGES}}, + sprintf("static constexpr uint16_t %-30s = %4d; //!< $name message ID\n", $msgid, $entry->{type}), + sprintf("static constexpr const char* %-30s = %-25s //!< $name message name\n", $strid, "\"${name}\";"), + ); + push(@{$CODEGEN_SECTIONS{FPSDK_COMMON_PARSER_SPARTN_MSGINFO}}, + sprintf(" { %-30s 0, %-30s \"%s\" },\n", "$msgid,", "$strid,", $entry->{desc}), + ); + } + push(@{$CODEGEN_SECTIONS{FPSDK_COMMON_PARSER_SPARTN_MSGINFO}}, + "}};\n", + "static constexpr std::array SUB_INFO =\n", + "{{\n"); + foreach my $entry (@SPARTN_SUBTYPES) + { + my $name = "SPARTN-$entry->{type}-$entry->{name}"; + my $msgid = "SPARTN_$entry->{type}_MSGID"; + my $subid = "SPARTN_$entry->{type}_$entry->{name}_SUBID"; + my $strid = "SPARTN_$entry->{type}_$entry->{name}_STRID"; + push(@{$CODEGEN_SECTIONS{FPSDK_COMMON_PARSER_SPARTN_MESSAGES}}, + sprintf("static constexpr uint16_t %-30s = %d; //!< $name message ID\n", $subid, $entry->{subtype}), + sprintf("static constexpr const char* %-30s = %-25s //!< $name message name\n", $strid, "\"${name}\";"), + ); + push(@{$CODEGEN_SECTIONS{FPSDK_COMMON_PARSER_SPARTN_MSGINFO}}, + sprintf(" { %s, %s, %s, \"%s\" },\n", $msgid, $subid, $strid, $entry->{desc}), + ); + } + push(@{$CODEGEN_SECTIONS{FPSDK_COMMON_PARSER_SPARTN_MSGINFO}}, + "}};\n"); +}; + +######################################################################################################################## +# Update files as necessary + +# printf("CODEGEN_FILES=%s\n", Dumper(\@CODEGEN_FILES)); +# printf("CODEGEN_SECTIONS=%s\n", Dumper(\%CODEGEN_SECTIONS)); + +foreach my $file (@CODEGEN_FILES) +{ + my @lines = $file->lines(); + my $sha1 = Digest::SHA::sha1_hex(@lines); + + foreach my $section (sort keys %CODEGEN_SECTIONS) + { + my $in_block = 0; + my @new_lines = (); + foreach my $line (@lines) + { + if ($line =~ m{\@fp_codegen_end\{$section\}}) + { + $in_block = 0; + } + push(@new_lines, $line) unless ($in_block); + if ($line =~ m{\@fp_codegen_begin\{$section\}}) { + $in_block = 1; + push(@new_lines, @{$CODEGEN_SECTIONS{$section}}); + } + } + @lines = @new_lines; + } + my $new_sha1 = Digest::SHA::sha1_hex(@lines); + + if ($sha1 eq $new_sha1) + { + printf("up to date: %s\n", $file->relative($FPSDK_COMMON_DIR)); + } + else + { + printf("updating: %s\n", $file->relative($FPSDK_COMMON_DIR)); + $file->spew(@lines); + } +} + +######################################################################################################################## diff --git a/fpsdk_common/src/fpl.cpp b/fpsdk_common/src/fpl.cpp index 0658a33..592b413 100644 --- a/fpsdk_common/src/fpl.cpp +++ b/fpsdk_common/src/fpl.cpp @@ -21,6 +21,7 @@ /* PACKAGE */ #include "fpsdk_common/fpl.hpp" +#include "fpsdk_common/gnss.hpp" #include "fpsdk_common/logging.hpp" #include "fpsdk_common/path.hpp" #include "fpsdk_common/string.hpp" @@ -308,7 +309,7 @@ bool FplFileReader::Open(const std::string& path) fh_ = std::make_unique(path, std::ios::binary); } if (fh_->fail()) { - WARNING("FplFileReader: fail open %s: %s", path.c_str(), std::strerror(errno)); + WARNING("FplFileReader: fail open %s: %s", path.c_str(), fpsdk::common::string::StrError(errno).c_str()); fh_.reset(); return false; } @@ -469,15 +470,14 @@ LogStatus::LogStatus(const FplMessage& log_msg) pos_lat_ = status["pos_lat"].as(); pos_lon_ = status["pos_lon"].as(); pos_height_ = status["pos_height"].as(); - using GnssFixType = fpsdk::common::types::GnssFixType; + using GnssFixType = fpsdk::common::gnss::GnssFixType; const bool pos_avail = - ((pos_source_ > POS_SOURCE_UNKNOWN) && - ((GnssFixType)pos_fix_type_ > fpsdk::common::types::GnssFixType::FIX_NOFIX)); + ((pos_source_ > POS_SOURCE_UNKNOWN) && ((GnssFixType)pos_fix_type_ > GnssFixType::NOFIX)); const char* pos_source_str = (pos_source_ == POS_SOURCE_GNSS ? "GNSS" : (pos_source_ == POS_SOURCE_FUSION ? "FUSION" : "?")); info_ += " log_time=" + log_time_iso_ + fpsdk::common::string::Sprintf(" pos=%s/%s/%.6f/%.6f/%.0f", pos_source_str, - fpsdk::common::types::GnssFixTypeStr((GnssFixType)pos_fix_type_), + fpsdk::common::gnss::GnssFixTypeStr((GnssFixType)pos_fix_type_), pos_avail ? pos_lat_ : NAN, pos_avail ? pos_lon_ : NAN, pos_avail ? pos_height_ : NAN); } diff --git a/fpsdk_common/src/gnss.cpp b/fpsdk_common/src/gnss.cpp new file mode 100644 index 0000000..6a6eca9 --- /dev/null +++ b/fpsdk_common/src/gnss.cpp @@ -0,0 +1,401 @@ +/** + * \verbatim + * ___ ___ + * \ \ / / + * \ \/ / Copyright (c) Fixposition AG (www.fixposition.com) and contributors + * / /\ \ License: see the LICENSE file + * /__/ \__\ + * + * Based on work by flipflip (https://github.com/phkehl) + * \endverbatim + * + * @file + * @brief Fixposition SDK: GNSS types and utilities + */ + +/* LIBC/STL */ +#include +#include + +/* EXTERNAL */ + +/* PACKAGE */ +#include "fpsdk_common/gnss.hpp" +#include "fpsdk_common/parser/ubx.hpp" + +namespace fpsdk { +namespace common { +namespace gnss { +/* ****************************************************************************************************************** */ + +const char* GnssFixTypeStr(const GnssFixType fix_type) +{ + switch (fix_type) { // clang-format off + case GnssFixType::UNKNOWN: return "UNKNOWN"; + case GnssFixType::NOFIX: return "NOFIX"; + case GnssFixType::DRONLY: return "DRONLY"; + case GnssFixType::TIME: return "TIME"; + case GnssFixType::SPP_2D: return "SPP_2D"; + case GnssFixType::SPP_3D: return "SPP_3D"; + case GnssFixType::SPP_3D_DR: return "SPP_3D_DR"; + case GnssFixType::RTK_FLOAT: return "RTK_FLOAT"; + case GnssFixType::RTK_FIXED: return "RTK_FIXED"; + case GnssFixType::RTK_FLOAT_DR: return "RTK_FLOAT_DR"; + case GnssFixType::RTK_FIXED_DR: return "RTK_FIXED_DR"; + } // clang-format on + return "?"; +} + +// --------------------------------------------------------------------------------------------------------------------- + +const char* GnssStr(const Gnss gnss) +{ + switch (gnss) { // clang-format off + case Gnss::UNKNOWN: return "UNKNOWN"; + case Gnss::GPS: return "GPS"; + case Gnss::SBAS: return "SBAS"; + case Gnss::GAL: return "GAL"; + case Gnss::BDS: return "BDS"; + case Gnss::QZSS: return "QZSS"; + case Gnss::GLO: return "GLO"; + case Gnss::NAVIC: return "NAVIC"; + } // clang-format on + + return "?"; +} + +// --------------------------------------------------------------------------------------------------------------------- + +const char* SignalStr(const Signal signal) +{ + switch (signal) { // clang-format off + case Signal::UNKNOWN: return "UNKNOWN"; + case Signal::BDS_B1C: return "BDS_B1C"; + case Signal::BDS_B1I: return "BDS_B1I"; + case Signal::BDS_B2A: return "BDS_B2A"; + case Signal::BDS_B2I: return "BDS_B2I"; + case Signal::GAL_E1: return "GAL_E1"; + case Signal::GAL_E5A: return "GAL_E5A"; + case Signal::GAL_E5B: return "GAL_E5B"; + case Signal::GLO_L1OF: return "GLO_L1OF"; + case Signal::GLO_L2OF: return "GLO_L2OF"; + case Signal::GPS_L1CA: return "GPS_L1CA"; + case Signal::GPS_L2C: return "GPS_L2C"; + case Signal::GPS_L5: return "GPS_L5"; + case Signal::QZSS_L1CA: return "QZSS_L1CA"; + case Signal::QZSS_L1S: return "QZSS_L1S"; + case Signal::QZSS_L2C: return "QZSS_L2C"; + case Signal::QZSS_L5: return "QZSS_L5"; + case Signal::SBAS_L1CA: return "SBAS_L1CA"; + case Signal::NAVIC_L5A: return "NAVIC_L5A"; + } // clang-format on + + return "?"; +} + +// --------------------------------------------------------------------------------------------------------------------- + +const char* BandStr(const Band band) +{ + switch (band) { // clang-format off + case Band::UNKNOWN: return "UNKNOWN"; + case Band::L1: return "L1"; + case Band::L2: return "L2"; + case Band::L5: return "L5"; + } // clang-format on + + return "?"; +} + +// --------------------------------------------------------------------------------------------------------------------- + +Band SignalToBand(const Signal signal) +{ + switch (signal) { // clang-format off + case Signal::GPS_L1CA: /* FALLTHROUGH */ + case Signal::BDS_B1I: /* FALLTHROUGH */ + case Signal::BDS_B1C: /* FALLTHROUGH */ + case Signal::GAL_E1: /* FALLTHROUGH */ + case Signal::GLO_L1OF: /* FALLTHROUGH */ + case Signal::QZSS_L1CA: /* FALLTHROUGH */ + case Signal::QZSS_L1S: /* FALLTHROUGH */ + case Signal::SBAS_L1CA: return Band::L1; + case Signal::GPS_L2C: /* FALLTHROUGH */ + case Signal::BDS_B2A: /* FALLTHROUGH */ + case Signal::BDS_B2I: /* FALLTHROUGH */ + case Signal::GAL_E5B: /* FALLTHROUGH */ + case Signal::GLO_L2OF: /* FALLTHROUGH */ + case Signal::QZSS_L2C: return Band::L2; + case Signal::GPS_L5: /* FALLTHROUGH */ + case Signal::QZSS_L5: /* FALLTHROUGH */ + case Signal::GAL_E5A: /* FALLTHROUGH */ + case Signal::NAVIC_L5A: return Band::L5; + case Signal::UNKNOWN: return Band::UNKNOWN; + } // clang-format on + + return Band::UNKNOWN; +} + +// --------------------------------------------------------------------------------------------------------------------- + +const char* SatStr(const Sat sat) +{ + const Gnss gnss = SatToGnss(sat); + const SvNr svnr = SatToSvNr(sat); + + switch (gnss) { + case Gnss::GPS: { + static const std::array strs = + /* clang-format off */ {{ + "G01", "G02", "G03", "G04", "G05", "G06", "G07", "G08", "G09", "G10", + "G11", "G12", "G13", "G14", "G15", "G16", "G17", "G18", "G19", "G20", + "G21", "G22", "G23", "G24", "G25", "G26", "G27", "G28", "G29", "G30", + "G31", "G32" + }}; // clang-format on + const int ix = (int)svnr - (int)FIRST_GPS; + if ((ix < 0) || (ix >= (int)strs.size())) { + return "G??"; + } + return strs[ix]; + } + case Gnss::SBAS: { + static const std::array strs = + /* clang-format off */ {{ + "S20", "S21", "S22", "S23", "S24", "S25", "S26", "S27", "S28", "S29", + "S30", "S31", "S32", "S33", "S34", "S35", "S36", "S37", "S38", "S39", + "S40", "S41", "S42", "S43", "S44", "S45", "S46", "S47", "S48", "S49", + "S50", "S51", "S52", "S53", "S54", "S55", "S56", "S57", "S58" + }}; // clang-format on + const int ix = (int)svnr - (int)FIRST_SBAS; + if ((ix < 0) || (ix >= (int)strs.size())) { + return "S??"; + } + return strs[ix]; + } + case Gnss::GAL: { + static const std::array strs = + /* clang-format off */ {{ + "E01", "E02", "E03", "E04", "E05", "E06", "E07", "E08", "E09", "E10", + "E11", "E12", "E13", "E14", "E15", "E16", "E17", "E18", "E19", "E20", + "E21", "E22", "E23", "E24", "E25", "E26", "E27", "E28", "E29", "E30", + "E31", "E32", "E33", "E34", "E35", "E36" + }}; // clang-format on + const int ix = (int)svnr - (int)FIRST_GAL; + if ((ix < 0) || (ix >= (int)strs.size())) { + return "E??"; + } + return strs[ix]; + } + case Gnss::BDS: { + static const std::array strs = + /* clang-format off */ {{ + "C01", "C02", "C03", "C04", "C05", "C06", "C07", "C08", "C09", "C10", + "C11", "C12", "C13", "C14", "C15", "C16", "C17", "C18", "C19", "C20", + "C21", "C22", "C23", "C24", "C25", "C26", "C27", "C28", "C29", "C30", + "C31", "C32", "C33", "C34", "C35", "C36", "C37", "C38", "C30", "C40", + "C41", "C42", "C43", "C44", "C45", "C46", "C47", "C48", "C40", "C50", + "C51", "C52", "C53", "C54", "C55", "C56", "C57", "C58", "C50", "C60", + "C61", "C62", "C63" + }}; // clang-format on + const int ix = (int)svnr - (int)FIRST_BDS; + if ((ix < 0) || (ix >= (int)strs.size())) { + return "C??"; + } + return strs[ix]; + } + case Gnss::QZSS: { + static const std::array strs = /* clang-format off */ {{ + "J01", "J02", "J03", "J04", "J05", "J06", "J07", "J08", "J09", "J10" + }}; // clang-format on + const int ix = (int)svnr - (int)FIRST_QZSS; + if ((ix < 0) || (ix >= (int)strs.size())) { + return "J??"; + } + return strs[ix]; + } + case Gnss::GLO: { + static const std::array strs = + /* clang-format off */ {{ + "R01", "R02", "R03", "R04", "R05", "R06", "R07", "R08", "R09", "R10", + "R11", "R12", "R13", "R14", "R15", "R16", "R17", "R18", "R19", "R20", + "R21", "R22", "R23", "R24", "R25", "R26", "R27", "R28", "R29", "R30", + "R31", "R32" + }}; // clang-format on + const int ix = (int)svnr - (int)FIRST_GLO; + if ((ix < 0) || (ix >= (int)strs.size())) { + return "R??"; + } + return strs[ix]; + } + case Gnss::NAVIC: { + static const std::array strs = /* clang-format off */ {{ + "I01", "I02", "I03", "I04", "I05", "I06", "I07", "I08", "I09", "I10", + "I11", "I12", "I13", "I14" + }}; // clang-format on + const int ix = (int)svnr - (int)FIRST_NAVIC; + if ((ix < 0) || (ix >= (int)strs.size())) { + return "I??"; + } + return strs[ix]; + } + case Gnss::UNKNOWN: + break; + } + return "???"; +} + +// --------------------------------------------------------------------------------------------------------------------- + +Sat StrSat(const char* str) +{ + Sat sat = INVALID_SAT; + char c = '\0'; + uint8_t n = 0; + int len = 0; + if ((std::sscanf(str, "%c%" SCNu8 "%n", &c, &n, &len) == 2) && (len == 3)) { + // clang-format off + if (((uint8_t)c == types::EnumToVal(Gnss::GPS)) && (n >= FIRST_GPS) && (n < (FIRST_GPS + NUM_GPS))) { sat = GnssSvNrToSat(Gnss::GPS, n); } + else if (((uint8_t)c == types::EnumToVal(Gnss::SBAS)) && (n >= FIRST_SBAS) && (n < (FIRST_SBAS + NUM_SBAS))) { sat = GnssSvNrToSat(Gnss::SBAS, n); } + else if (((uint8_t)c == types::EnumToVal(Gnss::GAL)) && (n >= FIRST_GAL) && (n < (FIRST_GAL + NUM_GAL))) { sat = GnssSvNrToSat(Gnss::GAL, n); } + else if (((uint8_t)c == types::EnumToVal(Gnss::BDS)) && (n >= FIRST_BDS) && (n < (FIRST_BDS + NUM_BDS))) { sat = GnssSvNrToSat(Gnss::BDS, n); } + else if (((uint8_t)c == types::EnumToVal(Gnss::QZSS)) && (n >= FIRST_QZSS) && (n < (FIRST_QZSS + NUM_QZSS))) { sat = GnssSvNrToSat(Gnss::QZSS, n); } + else if (((uint8_t)c == types::EnumToVal(Gnss::GLO)) && (n >= FIRST_GLO) && (n < (FIRST_GLO + NUM_GLO))) { sat = GnssSvNrToSat(Gnss::GLO, n); } + else if (((uint8_t)c == types::EnumToVal(Gnss::NAVIC)) && (n >= FIRST_NAVIC) && (n < (FIRST_NAVIC + NUM_NAVIC))) { sat = GnssSvNrToSat(Gnss::NAVIC, n); } + } + return sat; +} + +// --------------------------------------------------------------------------------------------------------------------- + +Gnss UbxGnssIdToGnss(const uint8_t gnssId) +{ + using namespace parser::ubx; + switch (gnssId) { // clang-format off + case UBX_GNSSID_NONE: return Gnss::UNKNOWN; + case UBX_GNSSID_GPS: return Gnss::GPS; + case UBX_GNSSID_SBAS: return Gnss::SBAS; + case UBX_GNSSID_GAL: return Gnss::GAL; + case UBX_GNSSID_BDS: return Gnss::BDS; + case UBX_GNSSID_QZSS: return Gnss::QZSS; + case UBX_GNSSID_GLO: return Gnss::GLO; + case UBX_GNSSID_NAVIC: return Gnss::NAVIC; + } // clang-format on + return Gnss::UNKNOWN; +} + +// --------------------------------------------------------------------------------------------------------------------- + +Sat UbxGnssIdSvIdToSat(const uint8_t gnssId, const uint8_t svId) +{ + using namespace parser::ubx; + switch (gnssId) { + case UBX_GNSSID_GPS: + if ((svId >= UBX_FIRST_GPS) && (svId < (UBX_FIRST_GPS + UBX_NUM_GPS))) { + return GnssSvNrToSat(Gnss::GPS, svId - UBX_FIRST_GPS + FIRST_GPS); + } + break; + case UBX_GNSSID_SBAS: + if ((svId >= UBX_FIRST_SBAS) && (svId < (UBX_FIRST_SBAS + UBX_NUM_SBAS))) { + return GnssSvNrToSat(Gnss::SBAS, svId - UBX_FIRST_SBAS + FIRST_SBAS); + } + break; + case UBX_GNSSID_GAL: + if ((svId >= UBX_FIRST_GAL) && (svId < (UBX_FIRST_GAL + UBX_NUM_GAL))) { + return GnssSvNrToSat(Gnss::GAL, svId - UBX_FIRST_GAL + FIRST_GAL); + } + break; + case UBX_GNSSID_BDS: + if ((svId >= UBX_FIRST_BDS) && (svId < (UBX_FIRST_BDS + UBX_NUM_BDS))) { + return GnssSvNrToSat(Gnss::BDS, svId - UBX_FIRST_BDS + FIRST_BDS); + } + break; + case UBX_GNSSID_QZSS: + if ((svId >= UBX_FIRST_QZSS) && (svId < (UBX_FIRST_QZSS + UBX_NUM_QZSS))) { + return GnssSvNrToSat(Gnss::QZSS, svId - UBX_FIRST_QZSS + FIRST_QZSS); + } + break; + case UBX_GNSSID_GLO: + if ((svId >= UBX_FIRST_GLO) && (svId < (UBX_FIRST_GLO + UBX_NUM_GLO))) { + return GnssSvNrToSat(Gnss::GLO, svId - UBX_FIRST_GLO + FIRST_GLO); + } + break; + case UBX_GNSSID_NAVIC: + if ((svId >= UBX_FIRST_NAVIC) && (svId < (UBX_FIRST_NAVIC + UBX_NUM_NAVIC))) { + return GnssSvNrToSat(Gnss::NAVIC, svId - UBX_FIRST_NAVIC + FIRST_NAVIC); + } + break; + } + return INVALID_SAT; +} + +// --------------------------------------------------------------------------------------------------------------------- + +Signal UbxGnssIdSigIdToSignal(const uint8_t gnssId, const uint8_t sigId) +{ + using namespace parser::ubx; + switch (gnssId) { // clang-format off + case UBX_GNSSID_GPS: + switch (sigId) { + case UBX_SIGID_GPS_L1CA: return Signal::GPS_L1CA; + case UBX_SIGID_GPS_L2CL: /* FALLTHROUGH */ + case UBX_SIGID_GPS_L2CM: return Signal::GPS_L2C; + case UBX_SIGID_GPS_L5I: /* FALLTHROUGH */ + case UBX_SIGID_GPS_L5Q: return Signal::GPS_L5; + } + break; + case UBX_GNSSID_SBAS: + switch (sigId) { + case UBX_SIGID_SBAS_L1CA: return Signal::SBAS_L1CA;; + } + break; + case UBX_GNSSID_GAL : + switch (sigId) { + case UBX_SIGID_GAL_E1C : /* FALLTHROUGH */ + case UBX_SIGID_GAL_E1B : return Signal::GAL_E1; + case UBX_SIGID_GAL_E5AI : /* FALLTHROUGH */ + case UBX_SIGID_GAL_E5AQ : return Signal::GAL_E5A; + case UBX_SIGID_GAL_E5BI : /* FALLTHROUGH */ + case UBX_SIGID_GAL_E5BQ : return Signal::GAL_E5B; + } + break; + case UBX_GNSSID_BDS : + switch (sigId) { + case UBX_SIGID_BDS_B1ID1: /* FALLTHROUGH */ + case UBX_SIGID_BDS_B1ID2: return Signal::BDS_B1I; + case UBX_SIGID_BDS_B1CD: /* FALLTHROUGH */ + case UBX_SIGID_BDS_B1CP: return Signal::BDS_B1C; + case UBX_SIGID_BDS_B2ID1: /* FALLTHROUGH */ + case UBX_SIGID_BDS_B2ID2: return Signal::BDS_B2I; + case UBX_SIGID_BDS_B2AP: /* FALLTHROUGH */ + case UBX_SIGID_BDS_B2AD: return Signal::BDS_B2A; + } + break; + case UBX_GNSSID_QZSS: + switch (sigId) { + case UBX_SIGID_QZSS_L1CA: return Signal::QZSS_L1CA; + case UBX_SIGID_QZSS_L1S : return Signal::QZSS_L1S; + case UBX_SIGID_QZSS_L2CM: /* FALLTHROUGH */ + case UBX_SIGID_QZSS_L2CL: return Signal::QZSS_L2C; + case UBX_SIGID_QZSS_L5I: /* FALLTHROUGH */ + case UBX_SIGID_QZSS_L5Q: return Signal::QZSS_L5; + } + break; + case UBX_GNSSID_GLO : + switch (sigId) { + case UBX_SIGID_GLO_L1OF: return Signal::GLO_L1OF; + case UBX_SIGID_GLO_L2OF: return Signal::GLO_L2OF; + } + break; + case UBX_GNSSID_NAVIC: + switch (sigId) { + case UBX_SIGID_NAVIC_L5A: return Signal::NAVIC_L5A; + } + break; + } // clang-format on + return Signal::UNKNOWN; +} + +/* ****************************************************************************************************************** */ +} // namespace gnss +} // namespace common +} // namespace fpsdk diff --git a/fpsdk_common/src/logging.cpp b/fpsdk_common/src/logging.cpp index 0a0067d..966ab8f 100644 --- a/fpsdk_common/src/logging.cpp +++ b/fpsdk_common/src/logging.cpp @@ -249,7 +249,7 @@ void LoggingPrint(const LoggingLevel level, const char* fmt, ...) // --------------------------------------------------------------------------------------------------------------------- void LoggingHexdump( - const LoggingLevel level, const uint8_t* data, const uint64_t size, const char* prefix, const char* fmt, ...) + const LoggingLevel level, const uint8_t* data, const std::size_t size, const char* prefix, const char* fmt, ...) { if (!LoggingIsLevel(level)) { return; @@ -266,7 +266,7 @@ void LoggingHexdump( const char i2hex[] = "0123456789abcdef"; const uint8_t* pData = data; - for (uint64_t ix = 0; ix < size;) { + for (std::size_t ix = 0; ix < size;) { char str[70]; std::memset(str, ' ', sizeof(str)); str[50] = '|'; diff --git a/fpsdk_common/src/parser.cpp b/fpsdk_common/src/parser.cpp index 71660f9..cf30539 100644 --- a/fpsdk_common/src/parser.cpp +++ b/fpsdk_common/src/parser.cpp @@ -5,6 +5,8 @@ * \ \/ / Copyright (c) Fixposition AG (www.fixposition.com) and contributors * / /\ \ License: see the LICENSE file * /__/ \__\ + * + * Based on work by flipflip (https://github.com/phkehl) * \endverbatim * * @file @@ -12,19 +14,733 @@ */ /* LIBC/STL */ +#include +#include +#include +#include /* EXTERNAL */ /* PACKAGE */ +#include "fpsdk_common/logging.hpp" #include "fpsdk_common/parser.hpp" +#include "fpsdk_common/parser/crc.hpp" +#include "fpsdk_common/parser/fpa.hpp" +#include "fpsdk_common/parser/fpb.hpp" +#include "fpsdk_common/parser/nmea.hpp" +#include "fpsdk_common/parser/novb.hpp" +#include "fpsdk_common/parser/rtcm3.hpp" +#include "fpsdk_common/parser/spartn.hpp" +#include "fpsdk_common/parser/ubx.hpp" +#include "fpsdk_common/parser/unib.hpp" namespace fpsdk { namespace common { namespace parser { /* ****************************************************************************************************************** */ +using namespace fpsdk::common::parser::crc; +using namespace fpsdk::common::parser::fpa; +using namespace fpsdk::common::parser::fpb; +using namespace fpsdk::common::parser::nmea; +using namespace fpsdk::common::parser::novb; +using namespace fpsdk::common::parser::rtcm3; +using namespace fpsdk::common::parser::spartn; +using namespace fpsdk::common::parser::ubx; +using namespace fpsdk::common::parser::unib; + +// --------------------------------------------------------------------------------------------------------------------- + +Parser::Parser() +{ + Reset(); +} + +// --------------------------------------------------------------------------------------------------------------------- + +void Parser::Reset() +{ + size_ = 0; + offs_ = 0; + stats_ = ParserStats(); +} + +// --------------------------------------------------------------------------------------------------------------------- + +bool Parser::Add(const uint8_t* data, const std::size_t size) +{ + if ((size == 0) || (data == NULL)) { + return false; + } + + // Overflow (no space for data) + if ((offs_ + size_ + size) > sizeof(buf_)) { + return false; + } + + // Add to buffer + std::memcpy(&buf_[offs_ + size_], data, size); + size_ += size; + return true; +} + +bool Parser::Add(const std::vector& data) +{ + return Add(data.data(), data.size()); +} + +// --------------------------------------------------------------------------------------------------------------------- + +/** + * @brief Detector functions to test the presence of a message in the buffer + * + * @param[in] buf Pointer to the buffer to check for presence of a message + * @param[in] size Size of data in buffer + * + * @returns either the special values NADA or WAIT, or the the message size + */ +using IsMessageFunc = std::function; +static constexpr int NADA = 0; //!< Indicates that there is no message in the buffer +static constexpr int WAIT = -1; //!< Indicates that more data is needed to decide (e.g., partial message in buffer) + +//! Check for presence of a UBX message?, in the buffer (see IsMessageFunc) +static int IsUbxMessage(const uint8_t* buf, const std::size_t size); +//! Check for presence of a NMEA (or FP_A) message in the buffer (see IsMessageFunc) +static int IsNmeaMessage(const uint8_t* buf, const std::size_t size); +//! Check for presence of a RTCM3 message in the buffer (see IsMessageFunc) +static int IsRtcm3Message(const uint8_t* buf, const std::size_t size); +//! Check for presence of a SPARTN message in the buffer (see IsMessageFunc) +static int IsSpartnMessage(const uint8_t* buf, const std::size_t size); +//! Check for presence of a NOV_B message in the buffer (see IsMessageFunc) +static int IsNovbMessage(const uint8_t* buf, const std::size_t size); +//! Check for presence of a FP_B message in the buffer (see IsMessageFunc) +static int IsFpbMessage(const uint8_t* buf, const std::size_t size); +//! Check for presence of a UNI_B message in the buffer (see IsMessageFunc) +static int IsUnibMessage(const uint8_t* buf, const std::size_t size); + +//! Helper for iterating through the different message frame detectors +struct ParserFunc +{ + IsMessageFunc is_message_func_; + Protocol proto_; + const char* proto_name_; +}; + +//! List of different message frame detectors +static const std::array PARSER_FUNCS = { { + // clang-format off + { IsFpbMessage, Protocol::FP_B, PROTOCOL_NAME_FP_B }, + { IsUbxMessage, Protocol::UBX, PROTOCOL_NAME_UBX }, + { IsNmeaMessage, Protocol::NMEA, PROTOCOL_NAME_NMEA }, + { IsRtcm3Message, Protocol::RTCM3, PROTOCOL_NAME_RTCM3 }, + { IsUnibMessage, Protocol::UNI_B, PROTOCOL_NAME_UNI_B }, + { IsNovbMessage, Protocol::NOV_B, PROTOCOL_NAME_NOV_B }, + { IsSpartnMessage, Protocol::SPARTN, PROTOCOL_NAME_SPARTN }, +}}; // clang-format on + +// --------------------------------------------------------------------------------------------------------------------- + +#if 0 +# define PARSER_TRACE(...) TRACE(__VA_ARGS__) +# define PARSER_TRACE_HEXDUMP(...) TRACE_HEXDUMP(__VA_ARGS__) +#else +# define PARSER_TRACE(...) /* nothing */ +# define PARSER_TRACE_HEXDUMP(...) /* nothing */ +#endif + +bool Parser::Process(ParserMsg& msg) +{ + while (size_ > 0) { + PARSER_TRACE_HEXDUMP( + &buf_[offs_], std::min(size_, (std::size_t)16), " ", "Parser: offs_=%d size_%d", (int)offs_, (int)size_); + + // Run parser functions + int msg_size = 0; + Protocol proto = Protocol::OTHER; + for (auto& parser : PARSER_FUNCS) { + msg_size = parser.is_message_func_(&buf_[offs_], size_); + PARSER_TRACE("process: try %s, msg_size=%d", parser.proto_name_, (int)msg_size); + + // Parser said: Wait, need more data + if (msg_size == WAIT) { + break; + } + // Parser said: I have a message + else if (msg_size > 0) { + proto = parser.proto_; + break; + } + // else (msg_size == NADA) // Parser said: Not my message + } + + // Waiting for more data... + if (msg_size == WAIT) { + PARSER_TRACE("process: need more data"); + return false; + } + + // No known message in buffer, move first byte to garbage + else if (msg_size == NADA) { + // buf: GGGG?????????????................ (offs_ >= 0, size_ > 0) + // --> buf: GGGGG????????????................ (offs_ > 0, size_ >= 0) + offs_++; + size_--; + PARSER_TRACE("process: collect garbage"); + + // Garbage bin full + if (offs_ >= MAX_OTHER_SIZE) { + EmitGarbage(msg); + return true; + } + } + + // We have a message (and come back to the same message in the next iteration) + else { // msgLen > 0 + // Return garbage first + if (offs_ > 0) { + EmitGarbage(msg); + return true; + } else { // offs_ == 0: Return message + EmitMessage(msg, msg_size, proto); + return true; + } + } + } + + // All data consumed, return garbage immediately if there is any + if (offs_ > 0) { + EmitGarbage(msg); + return true; + } + + return false; +} + +// --------------------------------------------------------------------------------------------------------------------- + +bool Parser::Flush(ParserMsg& msg) +{ + // buf: GGGGGGGGGGGGG???????????????........ + // --- offs_ --><-- size_ --> + // <---------- rem -----------> + const std::size_t rem = offs_ + size_; + if (rem > 0) { + if (rem > MAX_OTHER_SIZE) { + offs_ = MAX_OTHER_SIZE; + size_ = rem - offs_; + } else { + offs_ += size_; + size_ = 0; + } + EmitGarbage(msg); + return true; + } else { + return false; + } +} + +// --------------------------------------------------------------------------------------------------------------------- + +void Parser::EmitMessage(ParserMsg& msg, const std::size_t size, const Protocol proto) +{ + // Copy message to tmp, move remaining data to beginning of buf + // buf: MMMMMMMMMMMMMMM????????............. (offs_ = 0) + // <-- msg_size -> + // <------- size_ -------> + // --> tmp: MMMMMMMMMMMMMMM..... + // --> buf: ????????............................ (offs_ = 0, size_ >= 0) + + // PARSER_TRACE("msg copy tmp %d", size); + msg.data_ = { buf_, buf_ + size }; + // PARSER_TRACE("msg move 0 <- %d (%d)", size_ - size, size); + size_ -= size; + if (size_ > 0) { + std::memmove(&buf_[0], &buf_[size], size_); + } + stats_.s_msgs_ += size; + stats_.n_msgs_++; + // Make message + msg.proto_ = proto; + msg.seq_ = stats_.n_msgs_; + msg.info_.clear(); + char sname[MAX_NAME_SIZE]; + const uint8_t* mdata = msg.data_.data(); + const std::size_t msize = msg.data_.size(); + switch (proto) { // clang-format off + case Protocol::FP_A: // Handled in case Protocol::NMEA below // GCOVR_EXCL_LINE + break; // GCOVR_EXCL_LINE + case Protocol::FP_B: + stats_.n_fpb_++; + stats_.s_fpb_ += size; + msg.name_ = (FpbGetMessageName(sname, sizeof(sname), mdata, msize) ? sname : "FP_B-?"); // GCOVR_EXCL_LINE + break; + case Protocol::NMEA: // resp. FP_A + if ((msg.data_[1] == 'F') && (msg.data_[2] == 'P') && (msg.data_[3] == ',')) { + msg.name_ = (FpaGetMessageName(sname, sizeof(sname), mdata, msize) ? sname : "FP_A-?"); // GCOVR_EXCL_LINE + msg.proto_ = Protocol::FP_A; + stats_.n_fpa_++; + stats_.s_fpa_ += size; + } else { + msg.name_ = (NmeaGetMessageName(sname, sizeof(sname), mdata, msize) ? sname : "NMEA-?-?"); // GCOVR_EXCL_LINE + stats_.n_nmea_++; + stats_.s_nmea_ += size; + } + break; + case Protocol::UBX: + stats_.n_ubx_++; + stats_.s_ubx_ += size; + msg.name_ = (UbxGetMessageName(sname, sizeof(sname), mdata, msize) ? sname : "UBX-?-?"); // GCOVR_EXCL_LINE + break; + case Protocol::RTCM3: + stats_.n_rtcm3_++; + stats_.s_rtcm3_ += size; + msg.name_ = (Rtcm3GetMessageName(sname, sizeof(sname), mdata, msize) ? sname : "RTCM3-?"); // GCOVR_EXCL_LINE + break; + case Protocol::UNI_B: + stats_.n_unib_++; + stats_.s_unib_ += size; + msg.name_ = (UnibGetMessageName(sname, sizeof(sname), mdata, msize) ? sname : "UNI_B-?"); // GCOVR_EXCL_LINE + break; + case Protocol::NOV_B: + stats_.n_novb_++; + stats_.s_novb_ += size; + msg.name_ = (NovbGetMessageName(sname, sizeof(sname), mdata, msize) ? sname : "NOV_B-?"); // GCOVR_EXCL_LINE + break; + case Protocol::SPARTN: + stats_.n_spartn_++; + stats_.s_spartn_ += size; + msg.name_ = (SpartnGetMessageName(sname, sizeof(sname), mdata, msize) ? sname : "SPARTN-?-?"); // GCOVR_EXCL_LINE + break; + case Protocol::OTHER: // Handled in EmitGarbage() // GCOVR_EXCL_LINE + break; // GCOVR_EXCL_LINE + } // clang-format on + PARSER_TRACE("process: emit %s, size %d", msg.name_.c_str(), (int)msg.data_.size()); +} + +// --------------------------------------------------------------------------------------------------------------------- + +void Parser::EmitGarbage(ParserMsg& msg) +{ + // Copy garbage to msg buf and move data in parser buf + // buf: GGGGGGGGGGGGG???????????????........ (offs_ > 0, size_ >= 0) + // --- offs_ --><-- size_ --> + // --> tmp: GGGGGGGGGGGG...... + // --> buf ???????????????..................... (offs_ = 0, size_ >= 0) + const std::size_t size = offs_; + // PARSER_TRACE("garb copy tmp %d ", size); + msg.data_ = { buf_, buf_ + size }; + // PARSER_TRACE("garb move 0 <- %d (%d) ", size, size_); + std::memmove(&buf_[0], &buf_[size], size_); + offs_ = 0; + stats_.n_msgs_++; + stats_.s_msgs_ += size; + stats_.n_other_++; + stats_.s_other_ += size; + + // Make message + msg.proto_ = Protocol::OTHER; + msg.seq_ = stats_.n_msgs_; + msg.name_ = PROTOCOL_NAME_OTHER; + msg.info_.clear(); + PARSER_TRACE("process: emit %s, size %d ", msg.name_.c_str(), (int)msg.data_.size()); +} + +// --------------------------------------------------------------------------------------------------------------------- + +ParserStats Parser::GetStats() const +{ + return stats_; +} + +// --------------------------------------------------------------------------------------------------------------------- + +static int IsFpbMessage(const uint8_t* buf, const std::size_t size) +{ + // We need the two sync chars + if (buf[0] != FP_B_SYNC_1) { + return NADA; + } + if (size < 2) { + return WAIT; + } + if (buf[1] != FP_B_SYNC_2) { + return NADA; + } + + // Wait for full header + if (size < FP_B_HEAD_SIZE) { + return WAIT; + } + + // Limit payload size + const uint16_t payload_size = ((uint16_t)buf[4] | ((uint16_t)buf[5] << 8)); + if (payload_size > (MAX_FP_B_SIZE - FP_B_FRAME_SIZE)) { + return NADA; + } + + // Wait for entire message + if (size < (payload_size + FP_B_FRAME_SIZE)) { + return WAIT; + } + + // Verify using CRC + const uint32_t crc = *((uint32_t*)&buf[payload_size + FP_B_HEAD_SIZE]); + if (crc == Crc32fpb(&buf[0], payload_size + FP_B_HEAD_SIZE)) { + return payload_size + FP_B_FRAME_SIZE; + } + + return NADA; +} + +// --------------------------------------------------------------------------------------------------------------------- + +static int IsUbxMessage(const uint8_t* buf, const std::size_t size) +{ + // We need the two sync chars + if (buf[0] != UBX_SYNC_1) { + return NADA; + } + if (size < 2) { + return WAIT; + } + if (buf[1] != UBX_SYNC_2) { + return NADA; + } + + // Wait for full header + if (size < UBX_HEAD_SIZE) { + return WAIT; + } + + // Limit payload size + const std::size_t payload_size = ((uint16_t)buf[4] | ((uint16_t)buf[5] << 8)); + if (payload_size > (MAX_UBX_SIZE - UBX_FRAME_SIZE)) { + return NADA; + } + + // Wait for entire message + if (size < (payload_size + UBX_FRAME_SIZE)) { + return WAIT; + } + + // Verify using checksum + const uint16_t ck = *((uint16_t*)&buf[payload_size + UBX_HEAD_SIZE]); + if (ck == ChecksumUbx(&buf[2], payload_size + (UBX_HEAD_SIZE - 2))) { + return payload_size + UBX_FRAME_SIZE; + } + + return NADA; +} + +// --------------------------------------------------------------------------------------------------------------------- + +static int IsNmeaMessage(const uint8_t* buf, const std::size_t size) +{ + // Start of sentence + if (buf[0] != NMEA_PREAMBLE) { + return NADA; + } + + // Find end of sentence, calculate checksum along the way + std::size_t len = 1; // Length of sentence excl. "$" + uint8_t ck = 0; + while (true) { + if (len > MAX_NMEA_SIZE) { + return NADA; + } + if (len >= size) { // len doesn't include '$' + return WAIT; + } + if ((buf[len] == '\r') || (buf[len] == '\n') || (buf[len] == '*')) { + break; + } + // clang-format off + if ( // ((buf[len] & 0x80) != 0) || // 7-bit only + (buf[len] < 0x20) || (buf[len] > 0x7e) || // outside valid range + (buf[len] == '$') || (buf[len] == '\\') || (buf[len] == '!') || (buf[len] == '~') ) { // reserved + + return NADA; + } // clang-format on + ck ^= buf[len]; + len++; + } + + // Not nough data for sentence end (star + checksum + \r\n)? + if (size < (len + 1 + 2 + 2)) { + return WAIT; + } + + // Properly terminated sentence? + if ((buf[len] == '*') && (buf[len + 3] == '\r') && (buf[len + 4] == '\n')) { + uint8_t n1 = buf[len + 1]; + uint8_t n2 = buf[len + 2]; + uint8_t c1 = '0' + ((ck >> 4) & 0x0f); + uint8_t c2 = '0' + (ck & 0x0f); + if (c2 > '9') { + c2 += 'A' - '9' - 1; + } + // Checksum valid? + if ((n1 == c1) && (n2 == c2)) { + return len + 5; + } + } + + return NADA; +} + +// --------------------------------------------------------------------------------------------------------------------- + +static int IsRtcm3Message(const uint8_t* buf, const std::size_t size) +{ + // Not RTCM3 preamble? + if (buf[0] != RTCM3_PREAMBLE) { + return NADA; + } + + // Wait for enough data to look at header + if (size < RTCM3_HEAD_SIZE) { + return WAIT; + } + + // Check header + const uint16_t head = (uint16_t)buf[2] | ((uint16_t)buf[1] << 8); + const std::size_t payload_size = head & 0x03ff; // 10 bits + // const uint16_t empty = head & 0xfc00; // 6 bits + + // Too large? + const std::size_t msg_size = payload_size + RTCM3_FRAME_SIZE; + if ((msg_size > MAX_RTCM3_SIZE) /*|| (empty != 0x0000)*/) { + return NADA; + } + + // Wait for full message + if (size < msg_size) { + return WAIT; + } + + // CRC okay? + const uint32_t crc = + ((uint32_t)buf[msg_size - 3] << 16) | ((uint32_t)buf[msg_size - 2] << 8) | ((uint32_t)buf[msg_size - 1]); + if (crc == Crc24rtcm3(&buf[0], msg_size - 3)) { + return msg_size; + } + + return NADA; +} + // --------------------------------------------------------------------------------------------------------------------- +static int IsSpartnMessage(const uint8_t* buf, const std::size_t size) +{ + // Not RTCM3 preamble? + if (buf[0] != SPARTN_PREAMBLE) { + return NADA; + } + + // Wait for enough data to look at header + if (size < SPARTN_MIN_HEAD_SIZE) { + return WAIT; + } + + // byte 0 0b11111111 8 bits preamble + // byte 1 0b1111111. 7 bits message type + // const int proto = (buf[1] & 0xfe) >> 1; + // 0b.......1 . + // byte 2 0b11111111 10 bits payload length + // byte 3 0b1....... . + const std::size_t payload_size = + ((uint16_t)(buf[1] & 0x01) << 9) | ((uint16_t)buf[2] << 1) | (((uint16_t)buf[3] & 0x80) >> 7); + // 0b.1...... 1 bit encryption and authentication flag + const int enc_auth_flag = (buf[3] & 0x40) >> 6; + // 0b..11.... 2 bits crc type + const int crc_type = (buf[3] & 0x30) >> 4; + // 0b....1111 4 bits frame crc + const uint8_t frame_crc = (buf[3] & 0x0f); + uint8_t tmp[3] = { buf[1], buf[2], (uint8_t)(buf[3] & 0xf0) }; + if (frame_crc != Crc4spartn(tmp, sizeof(tmp))) { + return NADA; + } + // byte 4 0b1111.... 4 bits message subtype + // const int msgSubType = (buf[4] & 0xf0) >> 4; + // 0b....1... 1 bit time tag type + const int time_tag_type = (buf[4] & 0x08) >> 3; + // 0b.....111 . + // byte 5 0b11111111 16 bits gnss time tag + // 6 0b11111111 or 32 + // 7 0b11111111 + // byte 6 8 0b11111... . + // 0b.....111 . + // byte 7 9 0b1111.... . 7 bits solution id + // 0b....1111 4 bits slution processor id + std::size_t msg_size = (time_tag_type ? 10 : 8); + if (size < msg_size) { + return WAIT; + } + // if ea flag is set + // byte s 0b1111.... 4 bits encryption id + // byte s+1 0b....1111 . + // 0b11...... - 6 bits encryption sequence number + // 0b..111... - 3 bits authentication indicator + const int auth_ind = (buf[msg_size + 1] & 38) >> 3; + // 0b.....111 - 3 bits embedded authentication length + int ea_length = -1; + if (enc_auth_flag) { + if (auth_ind > 1) { + /*const int*/ ea_length = (buf[msg_size + 1] & 0x07); + const int ea_lengths[8] = { 8, 12, 16, 32, 64, 0, 0, 0 }; + msg_size += ea_lengths[ea_length]; + } + msg_size += 2; + } + // byte s+2... payload + msg_size += payload_size; + // message crc + const int crc_sizes[4] = { 1, 2, 3, 4 }; + msg_size += crc_sizes[crc_type]; + + if (size < msg_size) { + return WAIT; + } + + uint32_t msg_crc = 0; + uint32_t chk_crc = 0; + switch (crc_type) { + case 0: // FIXME: untested + msg_crc = (uint32_t)buf[msg_size - 1]; + chk_crc = Crc8spartn(&buf[1], msg_size - 1 - crc_sizes[crc_type]); + break; + case 1: // FIXME: untested + msg_crc = ((uint32_t)buf[msg_size - 2] << 8) | ((uint32_t)buf[msg_size - 1]); + chk_crc = Crc16spartn(&buf[1], msg_size - 1 - crc_sizes[crc_type]); + break; + case 2: // OK + msg_crc = ((uint32_t)buf[msg_size - 3] << 16) | ((uint32_t)buf[msg_size - 2] << 8) | + ((uint32_t)buf[msg_size - 1]); + chk_crc = Crc24rtcm3(&buf[1], msg_size - 1 - crc_sizes[crc_type]); + break; + case 3: // FIXME: untested + msg_crc = ((uint32_t)buf[msg_size - 4] << 24) | ((uint32_t)buf[msg_size - 3] << 16) | + ((uint32_t)buf[msg_size - 2] << 8) | ((uint32_t)buf[msg_size - 1]); + chk_crc = Crc32spartn(&buf[1], msg_size - 1 - crc_sizes[crc_type]); + break; + } + + if (msg_crc == chk_crc) { + return msg_size; + } + + return NADA; +} + +// --------------------------------------------------------------------------------------------------------------------- + +static int IsNovbMessage(const uint8_t* buf, const std::size_t size) +{ + // Need the correct three sync chars + if (buf[0] != NOV_B_SYNC_1) { + return NADA; + } + if (size < 3) { + return WAIT; + } + if ((buf[1] != NOV_B_SYNC_2) || ((buf[2] != NOV_B_SYNC_3_LONG) && (buf[2] != NOV_B_SYNC_3_SHORT))) { + return NADA; + } + + // https://docs.novatel.com/OEM7/Content/Messages/Binary.htm + // https://docs.novatel.com/OEM7/Content/Messages/Description_of_Short_Headers.htm + // Offset Type Long header Short header + // 0 uint8_t 0xaa uint8_t 0xaa + // 1 uint8_t 0x44 uint8_t 0x44 + // 2 uint8_t 0x12 uint8_t 0x13 + // 3 uint8_t header len uint8_t msg len + // 4 uint16_t msg ID uint16_t msg ID + // 6 uint8_t msg type uint16_t wno + // 7 uint8_t port addr + // 8 uint16_t msg len int32_t tow + // ... + // 3+hlen payload offs 13 payload + + if (size < 12) { + return WAIT; + } + + std::size_t len = 0; + + // Long header + if (buf[2] == NOV_B_SYNC_3_LONG) { + const uint8_t header_len = buf[3]; + const uint16_t msg_len = ((uint16_t)buf[9] << 8) | (uint16_t)buf[8]; + len = header_len + msg_len + sizeof(uint32_t); + } + // Short header + else { + const uint8_t header_len = 12; + const uint8_t msg_len = buf[3]; + len = header_len + msg_len + sizeof(uint32_t); + } + + // Discard too long messages + if (len > MAX_NOV_B_SIZE) { + return NADA; + } + + // Wait for full message + if (size < len) { + return WAIT; + } + + // Verify using CRC + const uint32_t crc = (buf[len - 1] << 24) | (buf[len - 2] << 16) | (buf[len - 3] << 8) | (buf[len - 4]); + if (crc == Crc32novb(buf, len - sizeof(uint32_t))) { + return len; + } + + return NADA; +} + +// --------------------------------------------------------------------------------------------------------------------- + +static int IsUnibMessage(const uint8_t* buf, const std::size_t size) +{ + // Need the correct three sync chars + if (buf[0] != UNI_B_SYNC_1) { + return NADA; + } + if (size < 3) { + return WAIT; + } + if ((buf[1] != UNI_B_SYNC_2) || (buf[2] != UNI_B_SYNC_3)) { + return NADA; + } + + // Wait for UnibHeader.size + if (size < 8) { + return WAIT; + } + + // Wait for complete message + const std::size_t len = sizeof(UnibHeader) + UnibMsgSize(buf) + sizeof(uint32_t); + + // Discard too long messages + if (len > MAX_UNI_B_SIZE) { + return NADA; + } + + // Wait for full message + if (size < len) { + return WAIT; + } + + // Verify using CRC + const uint32_t crc = (buf[len - 1] << 24) | (buf[len - 2] << 16) | (buf[len - 3] << 8) | (buf[len - 4]); + if (crc == Crc32novb(buf, len - sizeof(uint32_t))) { + return len; + } + + return NADA; +} + /* ****************************************************************************************************************** */ } // namespace parser } // namespace common diff --git a/fpsdk_common/src/parser/.gitkeep b/fpsdk_common/src/parser/.gitkeep deleted file mode 100644 index e69de29..0000000 diff --git a/fpsdk_common/src/parser/crc.cpp b/fpsdk_common/src/parser/crc.cpp new file mode 100644 index 0000000..90b54b1 --- /dev/null +++ b/fpsdk_common/src/parser/crc.cpp @@ -0,0 +1,408 @@ +/** + * \verbatim + * ___ ___ + * \ \ / / + * \ \/ / Copyright (c) Fixposition AG (www.fixposition.com) and contributors + * / /\ \ License: see the LICENSE file + * /__/ \__\ + * + * Based on work by flipflip (https://github.com/phkehl) + * \endverbatim + * + * @file + * @brief Fixposition SDK: Parser CRC routines + */ + +/* LIBC/STL */ +#include + +/* EXTERNAL */ + +/* PACKAGE */ +#include "fpsdk_common/parser/crc.hpp" + +namespace fpsdk { +namespace common { +namespace parser { +namespace crc { +/* ****************************************************************************************************************** */ + +// CRC tables generated using https://github.com/madler/crcany.git +// See also https://reveng.sourceforge.io/crc-catalogue/all.htm, https://users.ece.cmu.edu/~koopman/crc/, +// https://en.wikipedia.org/wiki/Cyclic_redundancy_check + +// --------------------------------------------------------------------------------------------------------------------- + +// clang-format off +// CRC table generated using https://github.com/madler/crcany.git, https://reveng.sourceforge.io/crc-catalogue/all.htm +// width=32 poly=0x32c00699 init=0x00000000 refin=false refout=false xorout=0x00000000 check=0x00000000 residue=0x000000 name="FF-FPB-32" +// The chosen polynomial is this one from http://users.ece.cmu.edu/~koopman/crc/crc32.html: +// (0x9960034c; 0x132c00699) <=> (0x9960034c; 0x132c00699) {65506,65506,32738,32738,193,193,31,31,17,17} | gold | (*o) CRC-32K/6.4 +// For HD = 5 and 6: 32738 data word length [bits], which is ~ 4 KiB, which is suitable for the expected FP_B maximum message size (of 1-2 KiB typically) +// clang-format on +static uint32_t const k_crc32_fpb[] = // clang-format off +{ + 0x00000000, 0x32c00699, 0x65800d32, 0x57400bab, 0xcb001a64, 0xf9c01cfd, + 0xae801756, 0x9c4011cf, 0xa4c03251, 0x960034c8, 0xc1403f63, 0xf38039fa, + 0x6fc02835, 0x5d002eac, 0x0a402507, 0x3880239e, 0x7b40623b, 0x498064a2, + 0x1ec06f09, 0x2c006990, 0xb040785f, 0x82807ec6, 0xd5c0756d, 0xe70073f4, + 0xdf80506a, 0xed4056f3, 0xba005d58, 0x88c05bc1, 0x14804a0e, 0x26404c97, + 0x7100473c, 0x43c041a5, 0xf680c476, 0xc440c2ef, 0x9300c944, 0xa1c0cfdd, + 0x3d80de12, 0x0f40d88b, 0x5800d320, 0x6ac0d5b9, 0x5240f627, 0x6080f0be, + 0x37c0fb15, 0x0500fd8c, 0x9940ec43, 0xab80eada, 0xfcc0e171, 0xce00e7e8, + 0x8dc0a64d, 0xbf00a0d4, 0xe840ab7f, 0xda80ade6, 0x46c0bc29, 0x7400bab0, + 0x2340b11b, 0x1180b782, 0x2900941c, 0x1bc09285, 0x4c80992e, 0x7e409fb7, + 0xe2008e78, 0xd0c088e1, 0x8780834a, 0xb54085d3, 0xdfc18e75, 0xed0188ec, + 0xba418347, 0x888185de, 0x14c19411, 0x26019288, 0x71419923, 0x43819fba, + 0x7b01bc24, 0x49c1babd, 0x1e81b116, 0x2c41b78f, 0xb001a640, 0x82c1a0d9, + 0xd581ab72, 0xe741adeb, 0xa481ec4e, 0x9641ead7, 0xc101e17c, 0xf3c1e7e5, + 0x6f81f62a, 0x5d41f0b3, 0x0a01fb18, 0x38c1fd81, 0x0041de1f, 0x3281d886, + 0x65c1d32d, 0x5701d5b4, 0xcb41c47b, 0xf981c2e2, 0xaec1c949, 0x9c01cfd0, + 0x29414a03, 0x1b814c9a, 0x4cc14731, 0x7e0141a8, 0xe2415067, 0xd08156fe, + 0x87c15d55, 0xb5015bcc, 0x8d817852, 0xbf417ecb, 0xe8017560, 0xdac173f9, + 0x46816236, 0x744164af, 0x23016f04, 0x11c1699d, 0x52012838, 0x60c12ea1, + 0x3781250a, 0x05412393, 0x9901325c, 0xabc134c5, 0xfc813f6e, 0xce4139f7, + 0xf6c11a69, 0xc4011cf0, 0x9341175b, 0xa18111c2, 0x3dc1000d, 0x0f010694, + 0x58410d3f, 0x6a810ba6, 0x8d431a73, 0xbf831cea, 0xe8c31741, 0xda0311d8, + 0x46430017, 0x7483068e, 0x23c30d25, 0x11030bbc, 0x29832822, 0x1b432ebb, + 0x4c032510, 0x7ec32389, 0xe2833246, 0xd04334df, 0x87033f74, 0xb5c339ed, + 0xf6037848, 0xc4c37ed1, 0x9383757a, 0xa14373e3, 0x3d03622c, 0x0fc364b5, + 0x58836f1e, 0x6a436987, 0x52c34a19, 0x60034c80, 0x3743472b, 0x058341b2, + 0x99c3507d, 0xab0356e4, 0xfc435d4f, 0xce835bd6, 0x7bc3de05, 0x4903d89c, + 0x1e43d337, 0x2c83d5ae, 0xb0c3c461, 0x8203c2f8, 0xd543c953, 0xe783cfca, + 0xdf03ec54, 0xedc3eacd, 0xba83e166, 0x8843e7ff, 0x1403f630, 0x26c3f0a9, + 0x7183fb02, 0x4343fd9b, 0x0083bc3e, 0x3243baa7, 0x6503b10c, 0x57c3b795, + 0xcb83a65a, 0xf943a0c3, 0xae03ab68, 0x9cc3adf1, 0xa4438e6f, 0x968388f6, + 0xc1c3835d, 0xf30385c4, 0x6f43940b, 0x5d839292, 0x0ac39939, 0x38039fa0, + 0x52829406, 0x6042929f, 0x37029934, 0x05c29fad, 0x99828e62, 0xab4288fb, + 0xfc028350, 0xcec285c9, 0xf642a657, 0xc482a0ce, 0x93c2ab65, 0xa102adfc, + 0x3d42bc33, 0x0f82baaa, 0x58c2b101, 0x6a02b798, 0x29c2f63d, 0x1b02f0a4, + 0x4c42fb0f, 0x7e82fd96, 0xe2c2ec59, 0xd002eac0, 0x8742e16b, 0xb582e7f2, + 0x8d02c46c, 0xbfc2c2f5, 0xe882c95e, 0xda42cfc7, 0x4602de08, 0x74c2d891, + 0x2382d33a, 0x1142d5a3, 0xa4025070, 0x96c256e9, 0xc1825d42, 0xf3425bdb, + 0x6f024a14, 0x5dc24c8d, 0x0a824726, 0x384241bf, 0x00c26221, 0x320264b8, + 0x65426f13, 0x5782698a, 0xcbc27845, 0xf9027edc, 0xae427577, 0x9c8273ee, + 0xdf42324b, 0xed8234d2, 0xbac23f79, 0x880239e0, 0x1442282f, 0x26822eb6, + 0x71c2251d, 0x43022384, 0x7b82001a, 0x49420683, 0x1e020d28, 0x2cc20bb1, + 0xb0821a7e, 0x82421ce7, 0xd502174c, 0xe7c211d5 +}; // clang-format on + +uint32_t Crc32fpb(const uint8_t* data, const std::size_t size) +{ + uint32_t crc = 0; + if (data != NULL) { + for (std::size_t ix = 0; ix < size; ix++) { + crc = (crc << 8) ^ k_crc32_fpb[((crc >> 24) ^ data[ix]) & 0xff]; + } + } + return crc; +} + +// --------------------------------------------------------------------------------------------------------------------- + +static const uint32_t k_crc24_rtcm3[256] = // clang-format off +{ + // width=24 poly=0x864cfb init=0x000000 refin=false refout=false xorout=0x000000 check=0x000000 residue=0x000000 name="RTCM3_SPARTN24" + 0x000000, 0x864cfb, 0x8ad50d, 0x0c99f6, 0x93e6e1, 0x15aa1a, 0x1933ec, 0x9f7f17, + 0xa18139, 0x27cdc2, 0x2b5434, 0xad18cf, 0x3267d8, 0xb42b23, 0xb8b2d5, 0x3efe2e, + 0xc54e89, 0x430272, 0x4f9b84, 0xc9d77f, 0x56a868, 0xd0e493, 0xdc7d65, 0x5a319e, + 0x64cfb0, 0xe2834b, 0xee1abd, 0x685646, 0xf72951, 0x7165aa, 0x7dfc5c, 0xfbb0a7, + 0x0cd1e9, 0x8a9d12, 0x8604e4, 0x00481f, 0x9f3708, 0x197bf3, 0x15e205, 0x93aefe, + 0xad50d0, 0x2b1c2b, 0x2785dd, 0xa1c926, 0x3eb631, 0xb8faca, 0xb4633c, 0x322fc7, + 0xc99f60, 0x4fd39b, 0x434a6d, 0xc50696, 0x5a7981, 0xdc357a, 0xd0ac8c, 0x56e077, + 0x681e59, 0xee52a2, 0xe2cb54, 0x6487af, 0xfbf8b8, 0x7db443, 0x712db5, 0xf7614e, + 0x19a3d2, 0x9fef29, 0x9376df, 0x153a24, 0x8a4533, 0x0c09c8, 0x00903e, 0x86dcc5, + 0xb822eb, 0x3e6e10, 0x32f7e6, 0xb4bb1d, 0x2bc40a, 0xad88f1, 0xa11107, 0x275dfc, + 0xdced5b, 0x5aa1a0, 0x563856, 0xd074ad, 0x4f0bba, 0xc94741, 0xc5deb7, 0x43924c, + 0x7d6c62, 0xfb2099, 0xf7b96f, 0x71f594, 0xee8a83, 0x68c678, 0x645f8e, 0xe21375, + 0x15723b, 0x933ec0, 0x9fa736, 0x19ebcd, 0x8694da, 0x00d821, 0x0c41d7, 0x8a0d2c, + 0xb4f302, 0x32bff9, 0x3e260f, 0xb86af4, 0x2715e3, 0xa15918, 0xadc0ee, 0x2b8c15, + 0xd03cb2, 0x567049, 0x5ae9bf, 0xdca544, 0x43da53, 0xc596a8, 0xc90f5e, 0x4f43a5, + 0x71bd8b, 0xf7f170, 0xfb6886, 0x7d247d, 0xe25b6a, 0x641791, 0x688e67, 0xeec29c, + 0x3347a4, 0xb50b5f, 0xb992a9, 0x3fde52, 0xa0a145, 0x26edbe, 0x2a7448, 0xac38b3, + 0x92c69d, 0x148a66, 0x181390, 0x9e5f6b, 0x01207c, 0x876c87, 0x8bf571, 0x0db98a, + 0xf6092d, 0x7045d6, 0x7cdc20, 0xfa90db, 0x65efcc, 0xe3a337, 0xef3ac1, 0x69763a, + 0x578814, 0xd1c4ef, 0xdd5d19, 0x5b11e2, 0xc46ef5, 0x42220e, 0x4ebbf8, 0xc8f703, + 0x3f964d, 0xb9dab6, 0xb54340, 0x330fbb, 0xac70ac, 0x2a3c57, 0x26a5a1, 0xa0e95a, + 0x9e1774, 0x185b8f, 0x14c279, 0x928e82, 0x0df195, 0x8bbd6e, 0x872498, 0x016863, + 0xfad8c4, 0x7c943f, 0x700dc9, 0xf64132, 0x693e25, 0xef72de, 0xe3eb28, 0x65a7d3, + 0x5b59fd, 0xdd1506, 0xd18cf0, 0x57c00b, 0xc8bf1c, 0x4ef3e7, 0x426a11, 0xc426ea, + 0x2ae476, 0xaca88d, 0xa0317b, 0x267d80, 0xb90297, 0x3f4e6c, 0x33d79a, 0xb59b61, + 0x8b654f, 0x0d29b4, 0x01b042, 0x87fcb9, 0x1883ae, 0x9ecf55, 0x9256a3, 0x141a58, + 0xefaaff, 0x69e604, 0x657ff2, 0xe33309, 0x7c4c1e, 0xfa00e5, 0xf69913, 0x70d5e8, + 0x4e2bc6, 0xc8673d, 0xc4fecb, 0x42b230, 0xddcd27, 0x5b81dc, 0x57182a, 0xd154d1, + 0x26359f, 0xa07964, 0xace092, 0x2aac69, 0xb5d37e, 0x339f85, 0x3f0673, 0xb94a88, + 0x87b4a6, 0x01f85d, 0x0d61ab, 0x8b2d50, 0x145247, 0x921ebc, 0x9e874a, 0x18cbb1, + 0xe37b16, 0x6537ed, 0x69ae1b, 0xefe2e0, 0x709df7, 0xf6d10c, 0xfa48fa, 0x7c0401, + 0x42fa2f, 0xc4b6d4, 0xc82f22, 0x4e63d9, 0xd11cce, 0x575035, 0x5bc9c3, 0xdd8538 +}; // clang-format on + +uint32_t Crc24rtcm3(const uint8_t* data, const std::size_t size) +{ + uint32_t crc = 0; + if (data != NULL) { + for (std::size_t ix = 0; ix < size; ix++) { + crc = (crc << 8) ^ k_crc24_rtcm3[((crc >> 16) ^ data[ix]) & 0xff]; + } + } + return crc & 0x00ffffff; +} + +// --------------------------------------------------------------------------------------------------------------------- + +static const uint32_t k_crc32_novb[256] = // clang-format off +{ + // width=32 poly=0x04c11db7 init=0x00000000 refin=true refout=false xorout=0x00000000 check=0x00000000 residue=0x000000 name="NOV_B-32" + 0x00000000, 0x77073096, 0xee0e612c, 0x990951ba, 0x076dc419, 0x706af48f, + 0xe963a535, 0x9e6495a3, 0x0edb8832, 0x79dcb8a4, 0xe0d5e91e, 0x97d2d988, + 0x09b64c2b, 0x7eb17cbd, 0xe7b82d07, 0x90bf1d91, 0x1db71064, 0x6ab020f2, + 0xf3b97148, 0x84be41de, 0x1adad47d, 0x6ddde4eb, 0xf4d4b551, 0x83d385c7, + 0x136c9856, 0x646ba8c0, 0xfd62f97a, 0x8a65c9ec, 0x14015c4f, 0x63066cd9, + 0xfa0f3d63, 0x8d080df5, 0x3b6e20c8, 0x4c69105e, 0xd56041e4, 0xa2677172, + 0x3c03e4d1, 0x4b04d447, 0xd20d85fd, 0xa50ab56b, 0x35b5a8fa, 0x42b2986c, + 0xdbbbc9d6, 0xacbcf940, 0x32d86ce3, 0x45df5c75, 0xdcd60dcf, 0xabd13d59, + 0x26d930ac, 0x51de003a, 0xc8d75180, 0xbfd06116, 0x21b4f4b5, 0x56b3c423, + 0xcfba9599, 0xb8bda50f, 0x2802b89e, 0x5f058808, 0xc60cd9b2, 0xb10be924, + 0x2f6f7c87, 0x58684c11, 0xc1611dab, 0xb6662d3d, 0x76dc4190, 0x01db7106, + 0x98d220bc, 0xefd5102a, 0x71b18589, 0x06b6b51f, 0x9fbfe4a5, 0xe8b8d433, + 0x7807c9a2, 0x0f00f934, 0x9609a88e, 0xe10e9818, 0x7f6a0dbb, 0x086d3d2d, + 0x91646c97, 0xe6635c01, 0x6b6b51f4, 0x1c6c6162, 0x856530d8, 0xf262004e, + 0x6c0695ed, 0x1b01a57b, 0x8208f4c1, 0xf50fc457, 0x65b0d9c6, 0x12b7e950, + 0x8bbeb8ea, 0xfcb9887c, 0x62dd1ddf, 0x15da2d49, 0x8cd37cf3, 0xfbd44c65, + 0x4db26158, 0x3ab551ce, 0xa3bc0074, 0xd4bb30e2, 0x4adfa541, 0x3dd895d7, + 0xa4d1c46d, 0xd3d6f4fb, 0x4369e96a, 0x346ed9fc, 0xad678846, 0xda60b8d0, + 0x44042d73, 0x33031de5, 0xaa0a4c5f, 0xdd0d7cc9, 0x5005713c, 0x270241aa, + 0xbe0b1010, 0xc90c2086, 0x5768b525, 0x206f85b3, 0xb966d409, 0xce61e49f, + 0x5edef90e, 0x29d9c998, 0xb0d09822, 0xc7d7a8b4, 0x59b33d17, 0x2eb40d81, + 0xb7bd5c3b, 0xc0ba6cad, 0xedb88320, 0x9abfb3b6, 0x03b6e20c, 0x74b1d29a, + 0xead54739, 0x9dd277af, 0x04db2615, 0x73dc1683, 0xe3630b12, 0x94643b84, + 0x0d6d6a3e, 0x7a6a5aa8, 0xe40ecf0b, 0x9309ff9d, 0x0a00ae27, 0x7d079eb1, + 0xf00f9344, 0x8708a3d2, 0x1e01f268, 0x6906c2fe, 0xf762575d, 0x806567cb, + 0x196c3671, 0x6e6b06e7, 0xfed41b76, 0x89d32be0, 0x10da7a5a, 0x67dd4acc, + 0xf9b9df6f, 0x8ebeeff9, 0x17b7be43, 0x60b08ed5, 0xd6d6a3e8, 0xa1d1937e, + 0x38d8c2c4, 0x4fdff252, 0xd1bb67f1, 0xa6bc5767, 0x3fb506dd, 0x48b2364b, + 0xd80d2bda, 0xaf0a1b4c, 0x36034af6, 0x41047a60, 0xdf60efc3, 0xa867df55, + 0x316e8eef, 0x4669be79, 0xcb61b38c, 0xbc66831a, 0x256fd2a0, 0x5268e236, + 0xcc0c7795, 0xbb0b4703, 0x220216b9, 0x5505262f, 0xc5ba3bbe, 0xb2bd0b28, + 0x2bb45a92, 0x5cb36a04, 0xc2d7ffa7, 0xb5d0cf31, 0x2cd99e8b, 0x5bdeae1d, + 0x9b64c2b0, 0xec63f226, 0x756aa39c, 0x026d930a, 0x9c0906a9, 0xeb0e363f, + 0x72076785, 0x05005713, 0x95bf4a82, 0xe2b87a14, 0x7bb12bae, 0x0cb61b38, + 0x92d28e9b, 0xe5d5be0d, 0x7cdcefb7, 0x0bdbdf21, 0x86d3d2d4, 0xf1d4e242, + 0x68ddb3f8, 0x1fda836e, 0x81be16cd, 0xf6b9265b, 0x6fb077e1, 0x18b74777, + 0x88085ae6, 0xff0f6a70, 0x66063bca, 0x11010b5c, 0x8f659eff, 0xf862ae69, + 0x616bffd3, 0x166ccf45, 0xa00ae278, 0xd70dd2ee, 0x4e048354, 0x3903b3c2, + 0xa7672661, 0xd06016f7, 0x4969474d, 0x3e6e77db, 0xaed16a4a, 0xd9d65adc, + 0x40df0b66, 0x37d83bf0, 0xa9bcae53, 0xdebb9ec5, 0x47b2cf7f, 0x30b5ffe9, + 0xbdbdf21c, 0xcabac28a, 0x53b39330, 0x24b4a3a6, 0xbad03605, 0xcdd70693, + 0x54de5729, 0x23d967bf, 0xb3667a2e, 0xc4614ab8, 0x5d681b02, 0x2a6f2b94, + 0xb40bbe37, 0xc30c8ea1, 0x5a05df1b, 0x2d02ef8d +}; // clang-format on + +uint32_t Crc32novb(const uint8_t* data, const std::size_t size) +{ + uint32_t crc = 0; + if (data != NULL) { + for (std::size_t ix = 0; ix < size; ix++) { + crc = (crc >> 8) ^ k_crc32_novb[(crc ^ data[ix]) & 0xff]; + } + } + return crc; +} + +// --------------------------------------------------------------------------------------------------------------------- + +static const uint8_t k_crc4_spartn[256] = // clang-format off +{ + // width=4 poly=0x9 init=0x0 refin=true refout=true xorout=0x0 check=0x0 residue=0x0 name="SPARTN-4" + 0x0, 0xb, 0x5, 0xe, 0xa, 0x1, 0xf, 0x4, 0x7, 0xc, 0x2, 0x9, 0xd, 0x6, 0x8, 0x3, + 0xe, 0x5, 0xb, 0x0, 0x4, 0xf, 0x1, 0xa, 0x9, 0x2, 0xc, 0x7, 0x3, 0x8, 0x6, 0xd, + 0xf, 0x4, 0xa, 0x1, 0x5, 0xe, 0x0, 0xb, 0x8, 0x3, 0xd, 0x6, 0x2, 0x9, 0x7, 0xc, + 0x1, 0xa, 0x4, 0xf, 0xb, 0x0, 0xe, 0x5, 0x6, 0xd, 0x3, 0x8, 0xc, 0x7, 0x9, 0x2, + 0xd, 0x6, 0x8, 0x3, 0x7, 0xc, 0x2, 0x9, 0xa, 0x1, 0xf, 0x4, 0x0, 0xb, 0x5, 0xe, + 0x3, 0x8, 0x6, 0xd, 0x9, 0x2, 0xc, 0x7, 0x4, 0xf, 0x1, 0xa, 0xe, 0x5, 0xb, 0x0, + 0x2, 0x9, 0x7, 0xc, 0x8, 0x3, 0xd, 0x6, 0x5, 0xe, 0x0, 0xb, 0xf, 0x4, 0xa, 0x1, + 0xc, 0x7, 0x9, 0x2, 0x6, 0xd, 0x3, 0x8, 0xb, 0x0, 0xe, 0x5, 0x1, 0xa, 0x4, 0xf, + 0x9, 0x2, 0xc, 0x7, 0x3, 0x8, 0x6, 0xd, 0xe, 0x5, 0xb, 0x0, 0x4, 0xf, 0x1, 0xa, + 0x7, 0xc, 0x2, 0x9, 0xd, 0x6, 0x8, 0x3, 0x0, 0xb, 0x5, 0xe, 0xa, 0x1, 0xf, 0x4, + 0x6, 0xd, 0x3, 0x8, 0xc, 0x7, 0x9, 0x2, 0x1, 0xa, 0x4, 0xf, 0xb, 0x0, 0xe, 0x5, + 0x8, 0x3, 0xd, 0x6, 0x2, 0x9, 0x7, 0xc, 0xf, 0x4, 0xa, 0x1, 0x5, 0xe, 0x0, 0xb, + 0x4, 0xf, 0x1, 0xa, 0xe, 0x5, 0xb, 0x0, 0x3, 0x8, 0x6, 0xd, 0x9, 0x2, 0xc, 0x7, + 0xa, 0x1, 0xf, 0x4, 0x0, 0xb, 0x5, 0xe, 0xd, 0x6, 0x8, 0x3, 0x7, 0xc, 0x2, 0x9, + 0xb, 0x0, 0xe, 0x5, 0x1, 0xa, 0x4, 0xf, 0xc, 0x7, 0x9, 0x2, 0x6, 0xd, 0x3, 0x8, + 0x5, 0xe, 0x0, 0xb, 0xf, 0x4, 0xa, 0x1, 0x2, 0x9, 0x7, 0xc, 0x8, 0x3, 0xd, 0x6 +}; // clang-format on + +uint8_t Crc4spartn(const uint8_t* data, const std::size_t size) +{ + uint8_t crc = 0; + if (data != NULL) { + for (std::size_t ix = 0; ix < size; ix++) { + crc = k_crc4_spartn[crc ^ data[ix]]; + } + } + return crc & 0x0f; +} + +// --------------------------------------------------------------------------------------------------------------------- + +static const uint8_t k_crc8_spartn[256] = // clang-format off +{ + // width=8 poly=0x07 init=0x00 refin=false refout=false xorout=0x0 check=0x0 residue=0x0 name="SPARTN-8" + 0x00, 0x07, 0x0e, 0x09, 0x1c, 0x1b, 0x12, 0x15, 0x38, 0x3f, 0x36, 0x31, 0x24, + 0x23, 0x2a, 0x2d, 0x70, 0x77, 0x7e, 0x79, 0x6c, 0x6b, 0x62, 0x65, 0x48, 0x4f, + 0x46, 0x41, 0x54, 0x53, 0x5a, 0x5d, 0xe0, 0xe7, 0xee, 0xe9, 0xfc, 0xfb, 0xf2, + 0xf5, 0xd8, 0xdf, 0xd6, 0xd1, 0xc4, 0xc3, 0xca, 0xcd, 0x90, 0x97, 0x9e, 0x99, + 0x8c, 0x8b, 0x82, 0x85, 0xa8, 0xaf, 0xa6, 0xa1, 0xb4, 0xb3, 0xba, 0xbd, 0xc7, + 0xc0, 0xc9, 0xce, 0xdb, 0xdc, 0xd5, 0xd2, 0xff, 0xf8, 0xf1, 0xf6, 0xe3, 0xe4, + 0xed, 0xea, 0xb7, 0xb0, 0xb9, 0xbe, 0xab, 0xac, 0xa5, 0xa2, 0x8f, 0x88, 0x81, + 0x86, 0x93, 0x94, 0x9d, 0x9a, 0x27, 0x20, 0x29, 0x2e, 0x3b, 0x3c, 0x35, 0x32, + 0x1f, 0x18, 0x11, 0x16, 0x03, 0x04, 0x0d, 0x0a, 0x57, 0x50, 0x59, 0x5e, 0x4b, + 0x4c, 0x45, 0x42, 0x6f, 0x68, 0x61, 0x66, 0x73, 0x74, 0x7d, 0x7a, 0x89, 0x8e, + 0x87, 0x80, 0x95, 0x92, 0x9b, 0x9c, 0xb1, 0xb6, 0xbf, 0xb8, 0xad, 0xaa, 0xa3, + 0xa4, 0xf9, 0xfe, 0xf7, 0xf0, 0xe5, 0xe2, 0xeb, 0xec, 0xc1, 0xc6, 0xcf, 0xc8, + 0xdd, 0xda, 0xd3, 0xd4, 0x69, 0x6e, 0x67, 0x60, 0x75, 0x72, 0x7b, 0x7c, 0x51, + 0x56, 0x5f, 0x58, 0x4d, 0x4a, 0x43, 0x44, 0x19, 0x1e, 0x17, 0x10, 0x05, 0x02, + 0x0b, 0x0c, 0x21, 0x26, 0x2f, 0x28, 0x3d, 0x3a, 0x33, 0x34, 0x4e, 0x49, 0x40, + 0x47, 0x52, 0x55, 0x5c, 0x5b, 0x76, 0x71, 0x78, 0x7f, 0x6a, 0x6d, 0x64, 0x63, + 0x3e, 0x39, 0x30, 0x37, 0x22, 0x25, 0x2c, 0x2b, 0x06, 0x01, 0x08, 0x0f, 0x1a, + 0x1d, 0x14, 0x13, 0xae, 0xa9, 0xa0, 0xa7, 0xb2, 0xb5, 0xbc, 0xbb, 0x96, 0x91, + 0x98, 0x9f, 0x8a, 0x8d, 0x84, 0x83, 0xde, 0xd9, 0xd0, 0xd7, 0xc2, 0xc5, 0xcc, + 0xcb, 0xe6, 0xe1, 0xe8, 0xef, 0xfa, 0xfd, 0xf4, 0xf3 +}; // clang-format on + +uint8_t Crc8spartn(const uint8_t* data, const std::size_t size) +{ + uint8_t crc = 0; + if (data != NULL) { + for (std::size_t ix = 0; ix < size; ix++) { + crc = k_crc8_spartn[crc ^ data[ix]]; + } + } + return crc & 0x000000ff; +} + +// --------------------------------------------------------------------------------------------------------------------- + +static const uint16_t k_crc16_spartn[256] = // clang-format off +{ + // width=16 poly=0x1021 init=0x0000 refin=false refout=false xorout=0x0000 check=0x0000 residue=0x0000 name="SPARTN-16" + 0x0000, 0x1021, 0x2042, 0x3063, 0x4084, 0x50a5, 0x60c6, 0x70e7, 0x8108, 0x9129, + 0xa14a, 0xb16b, 0xc18c, 0xd1ad, 0xe1ce, 0xf1ef, 0x1231, 0x0210, 0x3273, 0x2252, + 0x52b5, 0x4294, 0x72f7, 0x62d6, 0x9339, 0x8318, 0xb37b, 0xa35a, 0xd3bd, 0xc39c, + 0xf3ff, 0xe3de, 0x2462, 0x3443, 0x0420, 0x1401, 0x64e6, 0x74c7, 0x44a4, 0x5485, + 0xa56a, 0xb54b, 0x8528, 0x9509, 0xe5ee, 0xf5cf, 0xc5ac, 0xd58d, 0x3653, 0x2672, + 0x1611, 0x0630, 0x76d7, 0x66f6, 0x5695, 0x46b4, 0xb75b, 0xa77a, 0x9719, 0x8738, + 0xf7df, 0xe7fe, 0xd79d, 0xc7bc, 0x48c4, 0x58e5, 0x6886, 0x78a7, 0x0840, 0x1861, + 0x2802, 0x3823, 0xc9cc, 0xd9ed, 0xe98e, 0xf9af, 0x8948, 0x9969, 0xa90a, 0xb92b, + 0x5af5, 0x4ad4, 0x7ab7, 0x6a96, 0x1a71, 0x0a50, 0x3a33, 0x2a12, 0xdbfd, 0xcbdc, + 0xfbbf, 0xeb9e, 0x9b79, 0x8b58, 0xbb3b, 0xab1a, 0x6ca6, 0x7c87, 0x4ce4, 0x5cc5, + 0x2c22, 0x3c03, 0x0c60, 0x1c41, 0xedae, 0xfd8f, 0xcdec, 0xddcd, 0xad2a, 0xbd0b, + 0x8d68, 0x9d49, 0x7e97, 0x6eb6, 0x5ed5, 0x4ef4, 0x3e13, 0x2e32, 0x1e51, 0x0e70, + 0xff9f, 0xefbe, 0xdfdd, 0xcffc, 0xbf1b, 0xaf3a, 0x9f59, 0x8f78, 0x9188, 0x81a9, + 0xb1ca, 0xa1eb, 0xd10c, 0xc12d, 0xf14e, 0xe16f, 0x1080, 0x00a1, 0x30c2, 0x20e3, + 0x5004, 0x4025, 0x7046, 0x6067, 0x83b9, 0x9398, 0xa3fb, 0xb3da, 0xc33d, 0xd31c, + 0xe37f, 0xf35e, 0x02b1, 0x1290, 0x22f3, 0x32d2, 0x4235, 0x5214, 0x6277, 0x7256, + 0xb5ea, 0xa5cb, 0x95a8, 0x8589, 0xf56e, 0xe54f, 0xd52c, 0xc50d, 0x34e2, 0x24c3, + 0x14a0, 0x0481, 0x7466, 0x6447, 0x5424, 0x4405, 0xa7db, 0xb7fa, 0x8799, 0x97b8, + 0xe75f, 0xf77e, 0xc71d, 0xd73c, 0x26d3, 0x36f2, 0x0691, 0x16b0, 0x6657, 0x7676, + 0x4615, 0x5634, 0xd94c, 0xc96d, 0xf90e, 0xe92f, 0x99c8, 0x89e9, 0xb98a, 0xa9ab, + 0x5844, 0x4865, 0x7806, 0x6827, 0x18c0, 0x08e1, 0x3882, 0x28a3, 0xcb7d, 0xdb5c, + 0xeb3f, 0xfb1e, 0x8bf9, 0x9bd8, 0xabbb, 0xbb9a, 0x4a75, 0x5a54, 0x6a37, 0x7a16, + 0x0af1, 0x1ad0, 0x2ab3, 0x3a92, 0xfd2e, 0xed0f, 0xdd6c, 0xcd4d, 0xbdaa, 0xad8b, + 0x9de8, 0x8dc9, 0x7c26, 0x6c07, 0x5c64, 0x4c45, 0x3ca2, 0x2c83, 0x1ce0, 0x0cc1, + 0xef1f, 0xff3e, 0xcf5d, 0xdf7c, 0xaf9b, 0xbfba, 0x8fd9, 0x9ff8, 0x6e17, 0x7e36, + 0x4e55, 0x5e74, 0x2e93, 0x3eb2, 0x0ed1, 0x1ef0 +}; // clang-format on + +uint16_t Crc16spartn(const uint8_t* data, const std::size_t size) +{ + uint16_t crc = 0; + if (data != NULL) { + for (std::size_t ix = 0; ix < size; ix++) { + crc = (crc << 8) ^ k_crc16_spartn[((crc >> 8) ^ data[ix]) & 0xff]; + } + } + return crc; +} + +// --------------------------------------------------------------------------------------------------------------------- + +static const uint32_t k_crc32_spartn[256] = // clang-format off +{ + // width=32 poly=0x04c11db7 init=0xffffffff refin=false refout=false xorout=0xffffffff check=0x00000000 residue=0x000000 name="FF-SPARTN-32" + 0xb1f7404b, 0xb5365dfc, 0xb8757b25, 0xbcb46692, 0xa2f33697, 0xa6322b20, + 0xab710df9, 0xafb0104e, 0x97ffadf3, 0x933eb044, 0x9e7d969d, 0x9abc8b2a, + 0x84fbdb2f, 0x803ac698, 0x8d79e041, 0x89b8fdf6, 0xfde69b3b, 0xf927868c, + 0xf464a055, 0xf0a5bde2, 0xeee2ede7, 0xea23f050, 0xe760d689, 0xe3a1cb3e, + 0xdbee7683, 0xdf2f6b34, 0xd26c4ded, 0xd6ad505a, 0xc8ea005f, 0xcc2b1de8, + 0xc1683b31, 0xc5a92686, 0x29d4f6ab, 0x2d15eb1c, 0x2056cdc5, 0x2497d072, + 0x3ad08077, 0x3e119dc0, 0x3352bb19, 0x3793a6ae, 0x0fdc1b13, 0x0b1d06a4, + 0x065e207d, 0x029f3dca, 0x1cd86dcf, 0x18197078, 0x155a56a1, 0x119b4b16, + 0x65c52ddb, 0x6104306c, 0x6c4716b5, 0x68860b02, 0x76c15b07, 0x720046b0, + 0x7f436069, 0x7b827dde, 0x43cdc063, 0x470cddd4, 0x4a4ffb0d, 0x4e8ee6ba, + 0x50c9b6bf, 0x5408ab08, 0x594b8dd1, 0x5d8a9066, 0x8571303c, 0x81b02d8b, + 0x8cf30b52, 0x883216e5, 0x967546e0, 0x92b45b57, 0x9ff77d8e, 0x9b366039, + 0xa379dd84, 0xa7b8c033, 0xaafbe6ea, 0xae3afb5d, 0xb07dab58, 0xb4bcb6ef, + 0xb9ff9036, 0xbd3e8d81, 0xc960eb4c, 0xcda1f6fb, 0xc0e2d022, 0xc423cd95, + 0xda649d90, 0xdea58027, 0xd3e6a6fe, 0xd727bb49, 0xef6806f4, 0xeba91b43, + 0xe6ea3d9a, 0xe22b202d, 0xfc6c7028, 0xf8ad6d9f, 0xf5ee4b46, 0xf12f56f1, + 0x1d5286dc, 0x19939b6b, 0x14d0bdb2, 0x1011a005, 0x0e56f000, 0x0a97edb7, + 0x07d4cb6e, 0x0315d6d9, 0x3b5a6b64, 0x3f9b76d3, 0x32d8500a, 0x36194dbd, + 0x285e1db8, 0x2c9f000f, 0x21dc26d6, 0x251d3b61, 0x51435dac, 0x5582401b, + 0x58c166c2, 0x5c007b75, 0x42472b70, 0x468636c7, 0x4bc5101e, 0x4f040da9, + 0x774bb014, 0x738aada3, 0x7ec98b7a, 0x7a0896cd, 0x644fc6c8, 0x608edb7f, + 0x6dcdfda6, 0x690ce011, 0xd8fba0a5, 0xdc3abd12, 0xd1799bcb, 0xd5b8867c, + 0xcbffd679, 0xcf3ecbce, 0xc27ded17, 0xc6bcf0a0, 0xfef34d1d, 0xfa3250aa, + 0xf7717673, 0xf3b06bc4, 0xedf73bc1, 0xe9362676, 0xe47500af, 0xe0b41d18, + 0x94ea7bd5, 0x902b6662, 0x9d6840bb, 0x99a95d0c, 0x87ee0d09, 0x832f10be, + 0x8e6c3667, 0x8aad2bd0, 0xb2e2966d, 0xb6238bda, 0xbb60ad03, 0xbfa1b0b4, + 0xa1e6e0b1, 0xa527fd06, 0xa864dbdf, 0xaca5c668, 0x40d81645, 0x44190bf2, + 0x495a2d2b, 0x4d9b309c, 0x53dc6099, 0x571d7d2e, 0x5a5e5bf7, 0x5e9f4640, + 0x66d0fbfd, 0x6211e64a, 0x6f52c093, 0x6b93dd24, 0x75d48d21, 0x71159096, + 0x7c56b64f, 0x7897abf8, 0x0cc9cd35, 0x0808d082, 0x054bf65b, 0x018aebec, + 0x1fcdbbe9, 0x1b0ca65e, 0x164f8087, 0x128e9d30, 0x2ac1208d, 0x2e003d3a, + 0x23431be3, 0x27820654, 0x39c55651, 0x3d044be6, 0x30476d3f, 0x34867088, + 0xec7dd0d2, 0xe8bccd65, 0xe5ffebbc, 0xe13ef60b, 0xff79a60e, 0xfbb8bbb9, + 0xf6fb9d60, 0xf23a80d7, 0xca753d6a, 0xceb420dd, 0xc3f70604, 0xc7361bb3, + 0xd9714bb6, 0xddb05601, 0xd0f370d8, 0xd4326d6f, 0xa06c0ba2, 0xa4ad1615, + 0xa9ee30cc, 0xad2f2d7b, 0xb3687d7e, 0xb7a960c9, 0xbaea4610, 0xbe2b5ba7, + 0x8664e61a, 0x82a5fbad, 0x8fe6dd74, 0x8b27c0c3, 0x956090c6, 0x91a18d71, + 0x9ce2aba8, 0x9823b61f, 0x745e6632, 0x709f7b85, 0x7ddc5d5c, 0x791d40eb, + 0x675a10ee, 0x639b0d59, 0x6ed82b80, 0x6a193637, 0x52568b8a, 0x5697963d, + 0x5bd4b0e4, 0x5f15ad53, 0x4152fd56, 0x4593e0e1, 0x48d0c638, 0x4c11db8f, + 0x384fbd42, 0x3c8ea0f5, 0x31cd862c, 0x350c9b9b, 0x2b4bcb9e, 0x2f8ad629, + 0x22c9f0f0, 0x2608ed47, 0x1e4750fa, 0x1a864d4d, 0x17c56b94, 0x13047623, + 0x0d432626, 0x09823b91, 0x04c11d48, 0x000000ff +}; // clang-format on + +uint32_t Crc32spartn(const uint8_t* data, const std::size_t size) +{ + uint32_t crc = 0; + if (data != NULL) { + for (std::size_t ix = 0; ix < size; ix++) { + crc = (crc << 8) ^ k_crc32_spartn[((crc >> 24) ^ data[ix]) & 0xff]; + } + } + return crc; +} + +// --------------------------------------------------------------------------------------------------------------------- + +uint16_t ChecksumUbx(const uint8_t* data, const std::size_t size) +{ + uint8_t a = 0; + uint8_t b = 0; + if (data != NULL) { + for (std::size_t ix = 0; ix < size; ix++) { + a += data[ix]; + b += a; + } + } + return ((uint16_t)b << 8) | (uint16_t)a; +} + +/* ****************************************************************************************************************** */ +} // namespace crc +} // namespace parser +} // namespace common +} // namespace fpsdk diff --git a/fpsdk_common/src/parser/fpa.cpp b/fpsdk_common/src/parser/fpa.cpp new file mode 100644 index 0000000..d44f582 --- /dev/null +++ b/fpsdk_common/src/parser/fpa.cpp @@ -0,0 +1,1123 @@ +/** + * \verbatim + * ___ ___ + * \ \ / / + * \ \/ / Copyright (c) Fixposition AG (www.fixposition.com) and contributors + * / /\ \ License: see the LICENSE file + * /__/ \__\ + * + * Based on work by flipflip (https://github.com/phkehl) + * \endverbatim + * + * @file + * @brief Fixposition SDK: Parser FP_A routines and types + */ + +/* LIBC/STL */ +// #include +#include +#include +// #include +// #include +#include +// #include + +/* EXTERNAL */ + +/* PACKAGE */ +#include "fpsdk_common/parser/fpa.hpp" +#include "fpsdk_common/parser/nmea.hpp" +#include "fpsdk_common/types.hpp" + +namespace fpsdk { +namespace common { +namespace parser { +namespace fpa { +/* ****************************************************************************************************************** */ + +bool FpaGetMessageMeta(FpaMessageMeta& meta, const uint8_t* msg, const std::size_t msg_size) +{ + if ((msg == NULL) || (msg_size < 10) || (msg[1] != 'F') || (msg[2] != 'P') || (msg[3] != ',')) { + return false; + } + meta.payload_ix0_ = 0; + meta.payload_ix1_ = 0; + meta.msg_version_ = -1; + + // 012345678901234567890123456789 + // $FP,ODOMETRY,1,........*XX\r\n + // $FP,VERSION*XX\r\n + // $FP,VERSION,*XX\r\n + + std::size_t i_ix = 4; + std::size_t o_ix = 0; + meta.msg_type_[0] = '\0'; + for (; (i_ix < (msg_size - 4)) && (o_ix < sizeof(meta.msg_type_)); i_ix++, o_ix++) { + if ((msg[i_ix] == ',') || (msg[i_ix] == '*')) { + meta.msg_type_[o_ix] = '\0'; + break; + } else { + meta.msg_type_[o_ix] = msg[i_ix]; + } + } + if (meta.msg_type_[0] == '\0') { + return false; + } + + if (msg[i_ix] == ',') { + i_ix++; + } + + if ((msg[i_ix] >= '0') && (msg[i_ix] <= '9') && ((msg[i_ix + 1] == ',') || (msg[i_ix + 1] == '*'))) { + meta.msg_version_ = msg[i_ix] - '0'; + i_ix++; + if (msg[i_ix] == ',') { + i_ix++; + } + } + + if (msg[i_ix] != '*') { + meta.payload_ix0_ = i_ix; + meta.payload_ix1_ = msg_size - 5 - 1; // "*XX\r\n" + } + + return true; +} + +// --------------------------------------------------------------------------------------------------------------------- + +bool FpaGetMessageName(char* name, const std::size_t size, const uint8_t* msg, const std::size_t msg_size) +{ + if ((name == NULL) || (size < 1)) { + return false; + } + name[0] = '\0'; + + FpaMessageMeta meta; + if (!FpaGetMessageMeta(meta, msg, msg_size)) { + return false; + } + + return std::snprintf(name, size, "FP_A-%s", meta.msg_type_[0] != '\0' ? meta.msg_type_ : "?") < (int)size; +} + +// --------------------------------------------------------------------------------------------------------------------- + +bool FpaGetMessageInfo(char* info, const std::size_t size, const uint8_t* msg, const std::size_t msg_size) +{ + if ((info == NULL) || (size < 1)) { + return false; + } + std::size_t len = 0; + FpaMessageMeta meta; + if (FpaGetMessageMeta(meta, msg, msg_size)) { + char fmt[20]; + snprintf(fmt, sizeof(fmt), "%%.%ds", meta.payload_ix1_ - meta.payload_ix0_ + 1); + len += snprintf(info, size, fmt, (const char*)&msg[meta.payload_ix0_]); + } + return (len > 0) && (len < size); +} + +// --------------------------------------------------------------------------------------------------------------------- +// Various helpers for the SetFromMsg() FP_A decoding functions + +// Debug prints, for development +#if 0 +# define FPA_TRACE(fmt, ...) fprintf(stderr, fmt "\n", ##__VA_ARGS__) +#else +# define FPA_TRACE(fmt, ...) /* nothing */ +#endif + +// --------------------------------------------------------------------------------------------------------------------- + +// Parse float +static bool StrToFloat(const std::string& str, double& value) +{ + if (str.empty() || (std::isspace(str[0]) != 0)) { + return false; + } + + double value_tmp = 0.0f; + int num = 0; + int count = std::sscanf(str.data(), "%lf%n", &value_tmp, &num); + + if ((count == 1) && ((std::size_t)num == str.size()) && std::isfinite(value_tmp)) { + value = value_tmp; + return true; + } else { + return false; + } +} + +// Parse decimal (!) integer +static bool StrToInt(const std::string& str, int32_t& value) +{ + // No empty string, no leading whitespace + if (str.empty() || (std::isspace(str[0]) != 0)) { + return false; + } + + // Parse + int64_t value_tmp = 0; + int num = 0; + int count = std::sscanf(str.data(), "%" SCNd64 "%n", &value_tmp, &num); // *decimal* integer, so SCNd, not SCNi + // Number of values found must be 1 and the entire string must have been used (no trailing stuff) + if ((count == 1) && ((std::size_t)num == str.size()) && (value_tmp >= INT32_MIN) && (value_tmp <= INT32_MAX)) { + value = value_tmp; + return true; + } else { + return false; + } +} + +// --------------------------------------------------------------------------------------------------------------------- + +// Split NMEA sentence (message) into its meta data and the payload fields +struct FpaParts +{ + FpaMessageMeta meta_; + std::vector fields_; +}; + +static bool GetParts(FpaParts& parts, const char* msg_type, const uint8_t* msg, const std::size_t msg_size) +{ + bool ok = true; + + if (!FpaGetMessageMeta(parts.meta_, msg, msg_size) || (parts.meta_.payload_ix0_ <= 0) || + (parts.meta_.payload_ix1_ <= 0)) { + ok = false; + } else { + if (std::strcmp(parts.meta_.msg_type_, msg_type) != 0) { + ok = false; + } + + std::string payload((const char*)&msg[parts.meta_.payload_ix0_], + (const char*)&msg[parts.meta_.payload_ix0_] + (parts.meta_.payload_ix1_ - parts.meta_.payload_ix0_ + 1)); + + FPA_TRACE("GetParts(...) msg_type=%s msg_version=%d payload=%s ix0=%d ix1=%d size=%d", parts.meta_.msg_type_, + parts.meta_.msg_version_, payload.c_str(), parts.meta_.payload_ix0_, parts.meta_.payload_ix1_, msg_size); + + std::size_t pos = 0; + while ((pos = payload.find(",")) != std::string::npos) { + std::string part = payload.substr(0, pos); + payload.erase(0, pos + 1); + parts.fields_.push_back(part); + } + parts.fields_.push_back(payload); + } + + FPA_TRACE( + "GetParts(..., \"%s\", ..., ...)=%s #fields=%d", msg_type, ok ? "true" : "false", (int)parts.fields_.size()); + return ok; +} + +// --------------------------------------------------------------------------------------------------------------------- + +static bool GetInitStatus(FpaInitStatus& status, const std::string& field) +{ + bool ok = false; + status = FpaInitStatus::UNSPECIFIED; + if (!field.empty()) { + switch ((FpaInitStatus)field[0]) { // clang-format off + case FpaInitStatus::NOT_INIT: status = FpaInitStatus::NOT_INIT; ok = true; break; + case FpaInitStatus::LOCAL_INIT: status = FpaInitStatus::LOCAL_INIT; ok = true; break; + case FpaInitStatus::GLOBAL_INIT: status = FpaInitStatus::GLOBAL_INIT; ok = true; break; + case FpaInitStatus::UNSPECIFIED: break; + } // clang-format on + } else { + ok = true; + } + FPA_TRACE("GetInitStatus(\"%s\")=%s status=%c", field.c_str(), ok ? "true" : "false", types::EnumToVal(status)); + return ok; +} + +static bool GetFusionStatusLegacy(FpaFusionStatusLegacy& status, const std::string& field) +{ + bool ok = false; + status = FpaFusionStatusLegacy::UNSPECIFIED; + if (!field.empty()) { + switch ((FpaFusionStatusLegacy)field[0]) { // clang-format off + case FpaFusionStatusLegacy::NONE: status = FpaFusionStatusLegacy::NONE; ok = true; break; + case FpaFusionStatusLegacy::VISION: status = FpaFusionStatusLegacy::VISION; ok = true; break; + case FpaFusionStatusLegacy::VIO: status = FpaFusionStatusLegacy::VIO; ok = true; break; + case FpaFusionStatusLegacy::IMU_GNSS: status = FpaFusionStatusLegacy::IMU_GNSS; ok = true; break; + case FpaFusionStatusLegacy::VIO_GNSS: status = FpaFusionStatusLegacy::VIO_GNSS; ok = true; break; + case FpaFusionStatusLegacy::UNSPECIFIED: break; + } // clang-format on + } else { + ok = true; + } + FPA_TRACE( + "GetFusionStatusLegacy(\"%s\")=%s status=%c", field.c_str(), ok ? "true" : "false", types::EnumToVal(status)); + return ok; +} + +static bool GetMeasStatus(FpaMeasStatus& status, const std::string& field) +{ + bool ok = false; + status = FpaMeasStatus::UNSPECIFIED; + if (!field.empty()) { + switch ((FpaMeasStatus)field[0]) { // clang-format off + case FpaMeasStatus::NOT_USED: status = FpaMeasStatus::NOT_USED; ok = true; break; + case FpaMeasStatus::USED: status = FpaMeasStatus::USED; ok = true; break; + case FpaMeasStatus::DEGRADED: status = FpaMeasStatus::DEGRADED; ok = true; break; + case FpaMeasStatus::UNSPECIFIED: break; + } // clang-format on + } else { + ok = true; + } + FPA_TRACE("GetMeasStatus(\"%s\")=%s status=%c", field.c_str(), ok ? "true" : "false", types::EnumToVal(status)); + return ok; +} + +static bool GetImuStatus(FpaImuStatus& status, const std::string& field) +{ + bool ok = false; + status = FpaImuStatus::UNSPECIFIED; + if (!field.empty()) { + switch ((FpaImuStatus)field[0]) { // clang-format off + case FpaImuStatus::NOT_CONVERGED: status = FpaImuStatus::NOT_CONVERGED; ok = true; break; + case FpaImuStatus::WARMSTARTED: status = FpaImuStatus::WARMSTARTED; ok = true; break; + case FpaImuStatus::ROUGH_CONVERGED: status = FpaImuStatus::ROUGH_CONVERGED; ok = true; break; + case FpaImuStatus::FINE_CONVERGED: status = FpaImuStatus::FINE_CONVERGED; ok = true; break; + case FpaImuStatus::UNSPECIFIED: break; + } // clang-format on + } else { + ok = true; + } + FPA_TRACE("GetImuStatus(\"%s\")=%s status=%c", field.c_str(), ok ? "true" : "false", types::EnumToVal(status)); + return ok; +} + +static bool GetImuStatusLegacy(FpaImuStatusLegacy& status, const std::string& field) +{ + bool ok = false; + status = FpaImuStatusLegacy::UNSPECIFIED; + if (!field.empty()) { + switch ((FpaImuStatusLegacy)field[0]) { // clang-format off + case FpaImuStatusLegacy::NOT_CONVERGED: status = FpaImuStatusLegacy::NOT_CONVERGED; ok = true; break; + case FpaImuStatusLegacy::CONVERGED: status = FpaImuStatusLegacy::CONVERGED; ok = true; break; + case FpaImuStatusLegacy::UNSPECIFIED: break; + } // clang-format on + } else { + ok = true; + } + FPA_TRACE( + "GetImuStatusLegacy(\"%s\")=%s status=%c", field.c_str(), ok ? "true" : "false", types::EnumToVal(status)); + return ok; +} + +static bool GetImuNoise(FpaImuNoise& noise, const std::string& field) +{ + bool ok = false; + noise = FpaImuNoise::UNSPECIFIED; + if (!field.empty()) { + switch ((FpaImuNoise)field[0]) { // clang-format off + case FpaImuNoise::LOW_NOISE: noise = FpaImuNoise::LOW_NOISE; ok = true; break; + case FpaImuNoise::MEDIUM_NOISE: noise = FpaImuNoise::MEDIUM_NOISE; ok = true; break; + case FpaImuNoise::HIGH_NOISE: noise = FpaImuNoise::HIGH_NOISE; ok = true; break; + case FpaImuNoise::RESERVED4: noise = FpaImuNoise::RESERVED4; ok = true; break; + case FpaImuNoise::RESERVED5: noise = FpaImuNoise::RESERVED5; ok = true; break; + case FpaImuNoise::RESERVED6: noise = FpaImuNoise::RESERVED6; ok = true; break; + case FpaImuNoise::RESERVED7: noise = FpaImuNoise::RESERVED7; ok = true; break; + case FpaImuNoise::UNSPECIFIED: break; + } // clang-format on + } else { + ok = true; + } + FPA_TRACE("GetImuNoise(\"%s\")=%s noise=%c", field.c_str(), ok ? "true" : "false", types::EnumToVal(noise)); + return ok; +} + +static bool GetImuConv(FpaImuConv& conv, const std::string& field) +{ + bool ok = false; + conv = FpaImuConv::UNSPECIFIED; + if (!field.empty()) { + switch ((FpaImuConv)field[0]) { // clang-format off + case FpaImuConv::RESERVED0: conv = FpaImuConv::RESERVED0; ok = true; break; + case FpaImuConv::WAIT_IMU_MEAS: conv = FpaImuConv::WAIT_IMU_MEAS; ok = true; break; + case FpaImuConv::WAIT_GLOBAL_MEAS: conv = FpaImuConv::WAIT_GLOBAL_MEAS; ok = true; break; + case FpaImuConv::WAIT_MOTION: conv = FpaImuConv::WAIT_MOTION; ok = true; break; + case FpaImuConv::CONVERGING: conv = FpaImuConv::CONVERGING; ok = true; break; + case FpaImuConv::RESERVED5: conv = FpaImuConv::RESERVED5; ok = true; break; + case FpaImuConv::RESERVED6: conv = FpaImuConv::RESERVED6; ok = true; break; + case FpaImuConv::IDLE: conv = FpaImuConv::IDLE; ok = true; break; + case FpaImuConv::UNSPECIFIED: break; + } // clang-format on + } else { + ok = true; + } + FPA_TRACE("GetImuConv(\"%s\")=%s conv=%c", field.c_str(), ok ? "true" : "false", types::EnumToVal(conv)); + return ok; +} + +static bool GetGnssStatus(FpaGnssStatus& status, const std::string& field) +{ + bool ok = false; + status = FpaGnssStatus::UNSPECIFIED; + if (!field.empty()) { + switch ((FpaGnssStatus)field[0]) { // clang-format off + case FpaGnssStatus::NO_FIX: status = FpaGnssStatus::NO_FIX; ok = true; break; + case FpaGnssStatus::SPP: status = FpaGnssStatus::SPP; ok = true; break; + case FpaGnssStatus::RTK_MB: status = FpaGnssStatus::RTK_MB; ok = true; break; + case FpaGnssStatus::RESERVED3: status = FpaGnssStatus::RESERVED3; ok = true; break; + case FpaGnssStatus::RESERVED4: status = FpaGnssStatus::RESERVED4; ok = true; break; + case FpaGnssStatus::RTK_FLOAT: status = FpaGnssStatus::RTK_FLOAT; ok = true; break; + case FpaGnssStatus::RESERVED6: status = FpaGnssStatus::RESERVED6; ok = true; break; + case FpaGnssStatus::RESERVED7: status = FpaGnssStatus::RESERVED7; ok = true; break; + case FpaGnssStatus::RTK_FIXED: status = FpaGnssStatus::RTK_FIXED; ok = true; break; + case FpaGnssStatus::RESERVED9: status = FpaGnssStatus::RESERVED9; ok = true; break; + case FpaGnssStatus::UNSPECIFIED: break; + } // clang-format on + } else { + ok = true; + } + FPA_TRACE("GetGnssStatus(\"%s\")=%s status=%c", field.c_str(), ok ? "true" : "false", types::EnumToVal(status)); + return ok; +} + +static bool GetCorrStatus(FpaCorrStatus& status, const std::string& field) +{ + bool ok = false; + status = FpaCorrStatus::UNSPECIFIED; + if (!field.empty()) { + switch ((FpaCorrStatus)field[0]) { // clang-format off + case FpaCorrStatus::WAITING_FUSION: status = FpaCorrStatus::WAITING_FUSION; ok = true; break; + case FpaCorrStatus::NO_GNSS: status = FpaCorrStatus::NO_GNSS; ok = true; break; + case FpaCorrStatus::NO_CORR: status = FpaCorrStatus::NO_CORR; ok = true; break; + case FpaCorrStatus::LIMITED_CORR: status = FpaCorrStatus::LIMITED_CORR; ok = true; break; + case FpaCorrStatus::OLD_CORR: status = FpaCorrStatus::OLD_CORR; ok = true; break; + case FpaCorrStatus::GOOD_CORR: status = FpaCorrStatus::GOOD_CORR; ok = true; break; + case FpaCorrStatus::RESERVED6: status = FpaCorrStatus::RESERVED6; ok = true; break; + case FpaCorrStatus::RESERVED7: status = FpaCorrStatus::RESERVED7; ok = true; break; + case FpaCorrStatus::RESERVED8: status = FpaCorrStatus::RESERVED8; ok = true; break; + case FpaCorrStatus::RESERVED9: status = FpaCorrStatus::RESERVED9; ok = true; break; + case FpaCorrStatus::UNSPECIFIED: break; + } // clang-format on + } else { + ok = true; + } + FPA_TRACE("GetCorrStatus(\"%s\")=%s status=%c", field.c_str(), ok ? "true" : "false", types::EnumToVal(status)); + return ok; +} + +static bool GetBaselineStatus(FpaBaselineStatus& status, const std::string& field) +{ + bool ok = false; + status = FpaBaselineStatus::UNSPECIFIED; + if (!field.empty()) { + switch ((FpaBaselineStatus)field[0]) { // clang-format off + case FpaBaselineStatus::WAITING_FUSION: status = FpaBaselineStatus::WAITING_FUSION; ok = true; break; + case FpaBaselineStatus::NO_FIX: status = FpaBaselineStatus::NO_FIX; ok = true; break; + case FpaBaselineStatus::FAILING: status = FpaBaselineStatus::FAILING; ok = true; break; + case FpaBaselineStatus::PASSING: status = FpaBaselineStatus::PASSING; ok = true; break; + case FpaBaselineStatus::UNSPECIFIED: break; + } // clang-format on + } else { + ok = true; + } + FPA_TRACE("GetBaselineStatus(\"%s\")=%s status=%c", field.c_str(), ok ? "true" : "false", types::EnumToVal(status)); + return ok; +} + +static bool GetCamStatus(FpaCamStatus& status, const std::string& field) +{ + bool ok = false; + status = FpaCamStatus::UNSPECIFIED; + if (!field.empty()) { + switch ((FpaCamStatus)field[0]) { // clang-format off + case FpaCamStatus::CAM_UNAVL: status = FpaCamStatus::CAM_UNAVL; ok = true; break; + case FpaCamStatus::BAD_FEAT: status = FpaCamStatus::BAD_FEAT; ok = true; break; + case FpaCamStatus::RESERVED2: status = FpaCamStatus::RESERVED2; ok = true; break; + case FpaCamStatus::RESERVED3: status = FpaCamStatus::RESERVED3; ok = true; break; + case FpaCamStatus::RESERVED4: status = FpaCamStatus::RESERVED4; ok = true; break; + case FpaCamStatus::GOOD: status = FpaCamStatus::GOOD; ok = true; break; + case FpaCamStatus::UNSPECIFIED: break; + } // clang-format on + } else { + ok = true; + } + FPA_TRACE("GetCamStatus(\"%s\")=%s status=%c", field.c_str(), ok ? "true" : "false", types::EnumToVal(status)); + return ok; +} + +static bool GetWsStatus(FpaWsStatus& status, const std::string& field) +{ + bool ok = false; + status = FpaWsStatus::UNSPECIFIED; + if (!field.empty()) { + switch ((FpaWsStatus)field[0]) { // clang-format off + case FpaWsStatus::NOT_ENABLED: status = FpaWsStatus::NOT_ENABLED; ok = true; break; + case FpaWsStatus::MISS_MEAS: status = FpaWsStatus::MISS_MEAS; ok = true; break; + case FpaWsStatus::NONE_CONVERGED: status = FpaWsStatus::NONE_CONVERGED; ok = true; break; + case FpaWsStatus::ONE_CONVERGED: status = FpaWsStatus::ONE_CONVERGED; ok = true; break; + case FpaWsStatus::ALL_CONVERGED: status = FpaWsStatus::ALL_CONVERGED; ok = true; break; + case FpaWsStatus::UNSPECIFIED: break; + } // clang-format on + } else { + ok = true; + } + FPA_TRACE("GetWsStatus(\"%s\")=%s status=%c", field.c_str(), ok ? "true" : "false", types::EnumToVal(status)); + return ok; +} + +static bool GetWsStatusLegacy(FpaWsStatusLegacy& status, const std::string& field) +{ + bool ok = false; + status = FpaWsStatusLegacy::UNSPECIFIED; + if (!field.empty()) { + switch ((FpaWsStatusLegacy)field[0]) { // clang-format off + case FpaWsStatusLegacy::NOT_ENABLED: status = FpaWsStatusLegacy::NOT_ENABLED; ok = true; break; + case FpaWsStatusLegacy::NONE_CONVERGED: status = FpaWsStatusLegacy::NONE_CONVERGED; ok = true; break; + case FpaWsStatusLegacy::ONE_OR_MORE_CONVERGED: status = FpaWsStatusLegacy::ONE_OR_MORE_CONVERGED; ok = true; break; + case FpaWsStatusLegacy::UNSPECIFIED: break; + } // clang-format on + } else { + ok = true; + } + FPA_TRACE("GetWsStatusLegacy(\"%s\")=%s status=%c", field.c_str(), ok ? "true" : "false", types::EnumToVal(status)); + return ok; +} + +static bool GetWsConv(FpaWsConv& conv, const std::string& field) +{ + bool ok = false; + conv = FpaWsConv::UNSPECIFIED; + if (!field.empty()) { + switch ((FpaWsConv)field[0]) { // clang-format off + case FpaWsConv::WAIT_FUSION: conv = FpaWsConv::WAIT_FUSION; ok = true; break; + case FpaWsConv::WAIT_WS_MEAS: conv = FpaWsConv::WAIT_WS_MEAS; ok = true; break; + case FpaWsConv::WAIT_GLOBAL_MEAS: conv = FpaWsConv::WAIT_GLOBAL_MEAS; ok = true; break; + case FpaWsConv::WAIT_MOTION: conv = FpaWsConv::WAIT_MOTION; ok = true; break; + case FpaWsConv::WAIT_IMU_BIAS: conv = FpaWsConv::WAIT_IMU_BIAS; ok = true; break; + case FpaWsConv::CONVERGING: conv = FpaWsConv::CONVERGING; ok = true; break; + case FpaWsConv::IDLE: conv = FpaWsConv::IDLE; ok = true; break; + case FpaWsConv::UNSPECIFIED: break; + } // clang-format on + } else { + ok = true; + } + FPA_TRACE("GetWsConv(\"%s\")=%s conv=%c", field.c_str(), ok ? "true" : "false", types::EnumToVal(conv)); + return ok; +} + +static bool GetMarkersStatus(FpaMarkersStatus& status, const std::string& field) +{ + bool ok = false; + status = FpaMarkersStatus::UNSPECIFIED; + if (!field.empty()) { + switch ((FpaMarkersStatus)field[0]) { // clang-format off + case FpaMarkersStatus::NOT_ENABLED: status = FpaMarkersStatus::NOT_ENABLED; ok = true; break; + case FpaMarkersStatus::NONE_CONVERGED: status = FpaMarkersStatus::NONE_CONVERGED; ok = true; break; + case FpaMarkersStatus::ONE_CONVERGED: status = FpaMarkersStatus::ONE_CONVERGED; ok = true; break; + case FpaMarkersStatus::ALL_CONVERGED: status = FpaMarkersStatus::ALL_CONVERGED; ok = true; break; + case FpaMarkersStatus::UNSPECIFIED: break; + } // clang-format on + } else { + ok = true; + } + FPA_TRACE("GetMarkersStatus(\"%s\")=%s status=%c", field.c_str(), ok ? "true" : "false", types::EnumToVal(status)); + return ok; +} + +static bool GetMarkersConv(FpaMarkersConv& conv, const std::string& field) +{ + bool ok = false; + conv = FpaMarkersConv::UNSPECIFIED; + if (!field.empty()) { + switch ((FpaMarkersConv)field[0]) { // clang-format off + case FpaMarkersConv::WAIT_FUSION: conv = FpaMarkersConv::WAIT_FUSION; ok = true; break; + case FpaMarkersConv::WAIT_MARKER_MEAS: conv = FpaMarkersConv::WAIT_MARKER_MEAS; ok = true; break; + case FpaMarkersConv::WAIT_GLOBAL_MEAS: conv = FpaMarkersConv::WAIT_GLOBAL_MEAS; ok = true; break; + case FpaMarkersConv::CONVERGING: conv = FpaMarkersConv::CONVERGING; ok = true; break; + case FpaMarkersConv::IDLE: conv = FpaMarkersConv::IDLE; ok = true; break; + case FpaMarkersConv::UNSPECIFIED: break; + } // clang-format on + } else { + ok = true; + } + FPA_TRACE("GetMarkersConv(\"%s\")=%s conv=%c", field.c_str(), ok ? "true" : "false", types::EnumToVal(conv)); + return ok; +} + +static bool GetGnssFix(FpaGnssFix& fix, const std::string& field) +{ + bool ok = false; + fix = FpaGnssFix::UNSPECIFIED; + if (!field.empty()) { + switch ((FpaGnssFix)field[0]) { // clang-format off + case FpaGnssFix::UNKNOWN: fix = FpaGnssFix::UNKNOWN; ok = true; break; + case FpaGnssFix::NOFIX: fix = FpaGnssFix::NOFIX; ok = true; break; + case FpaGnssFix::DRONLY: fix = FpaGnssFix::DRONLY; ok = true; break; + case FpaGnssFix::TIME: fix = FpaGnssFix::TIME; ok = true; break; + case FpaGnssFix::S2D: fix = FpaGnssFix::S2D; ok = true; break; + case FpaGnssFix::S3D: fix = FpaGnssFix::S3D; ok = true; break; + case FpaGnssFix::S3D_DR: fix = FpaGnssFix::S3D_DR; ok = true; break; + case FpaGnssFix::RTK_FLOAT: fix = FpaGnssFix::RTK_FLOAT; ok = true; break; + case FpaGnssFix::RTK_FIXED: fix = FpaGnssFix::RTK_FIXED; ok = true; break; + case FpaGnssFix::UNSPECIFIED: break; + } // clang-format on + } else { + ok = true; + } + FPA_TRACE("GetGnssFix(\"%s\")=%s conv=%c", field.c_str(), ok ? "true" : "false", types::EnumToVal(fix)); + return ok; +} + +static bool GetEpoch(FpaEpoch& epoch, const std::string& field) +{ + bool ok = true; + if (!field.empty()) { // clang-format off + if (field == "GNSS1") { epoch = FpaEpoch::GNSS1; } + else if (field == "GNSS2") { epoch = FpaEpoch::GNSS2; } + else if (field == "GNSS") { epoch = FpaEpoch::GNSS; } + else if (field == "FUSION") { epoch = FpaEpoch::FUSION; } + else { ok = false; } // clang-format on + } else { + ok = false; + } + FPA_TRACE("GetEpoch(\"%s\")=%s epoch=%d", field.c_str(), ok ? "true" : "false", types::EnumToVal(epoch)); + return ok; +} + +static bool GetAntState(FpaAntState& state, const std::string& field) +{ + bool ok = true; // clang-format off + if (field == "ok") { state = FpaAntState::OK; } + else if (field == "open") { state = FpaAntState::OPEN; } + else if (field == "short") { state = FpaAntState::SHORT; } + else { state = FpaAntState::UNSPECIFIED; ok = field.empty(); } // clang-format on + FPA_TRACE("GetAntState(\"%s\")=%s state=%d", field.c_str(), ok ? "true" : "false", types::EnumToVal(state)); + return ok; +} + +static bool GetAntPower(FpaAntPower& power, const std::string& field) +{ + bool ok = true; // clang-format off + if (field == "on") { power = FpaAntPower::ON; } + else if (field == "off") { power = FpaAntPower::OFF; } + else { power = FpaAntPower::UNSPECIFIED; ok = field.empty(); } // clang-format on + FPA_TRACE("GetAntPower(\"%s\")=%s power=%d", field.c_str(), ok ? "true" : "false", types::EnumToVal(power)); + return ok; +} + +static bool GetTextLevel(FpaTextLevel& level, const std::string& field) +{ + bool ok = true; // clang-format off + if (field == "ERROR") { level = FpaTextLevel::ERROR; } + else if (field == "WARNING") { level = FpaTextLevel::WARNING; } + else if (field == "INFO") { level = FpaTextLevel::INFO; } + else if (field == "DEBUG") { level = FpaTextLevel::DEBUG; } + else { level = FpaTextLevel::UNSPECIFIED; ok = field.empty(); } // clang-format on + FPA_TRACE("GetTextLevel(\"%s\")=%s level=%d", field.c_str(), ok ? "true" : "false", types::EnumToVal(level)); + return ok; +} + +static bool GetTimebase(FpaTimebase& base, const std::string& field) +{ + bool ok = true; // clang-format off + if (field == "") { base = FpaTimebase::NONE; } + else if (field == "GNSS") { base = FpaTimebase::GNSS; } + else if (field == "UTC") { base = FpaTimebase::UTC; } + else if (field == "NONE") { base = FpaTimebase::NONE; } + else { base = FpaTimebase::UNSPECIFIED; ok = false; } // clang-format on + FPA_TRACE("GetTimebase(\"%s\")=%s base=%d", field.c_str(), ok ? "true" : "false", types::EnumToVal(base)); + return ok; +} + +static bool GetTimeref(FpaTimeref& ref, const std::string& field) +{ + bool ok = true; // clang-format off + if (field == "NONE") { ref = FpaTimeref::UTC_NONE; } + else if (field == "CRL") { ref = FpaTimeref::UTC_CRL; } + else if (field == "NIST") { ref = FpaTimeref::UTC_NIST; } + else if (field == "USNO") { ref = FpaTimeref::UTC_USNO; } + else if (field == "BIPM") { ref = FpaTimeref::UTC_BIPM; } + else if (field == "EU") { ref = FpaTimeref::UTC_EU; } + else if (field == "SU") { ref = FpaTimeref::UTC_SU; } + else if (field == "NTSC") { ref = FpaTimeref::UTC_NTSC; } + else if (field == "GPS") { ref = FpaTimeref::GNSS_GPS; } + else if (field == "GAL") { ref = FpaTimeref::GNSS_GAL; } + else if (field == "BDS") { ref = FpaTimeref::GNSS_BDS; } + else if (field == "GLO") { ref = FpaTimeref::GNSS_GLO; } + else if (field == "NVC") { ref = FpaTimeref::GNSS_NVC; } + else if (field == "OTHER") { ref = FpaTimeref::OTHER; } + else { ref = FpaTimeref::UNSPECIFIED; } // clang-format on + FPA_TRACE("GetTimeref(\"%s\")=%s ref=%d", field.c_str(), ok ? "true" : "false", types::EnumToVal(ref)); + return ok; +} + +static constexpr int INAN = std::numeric_limits::max(); + +// Get integer value +static bool GetInt( + FpaInt& fpaint, const std::string& field, const bool required, const int min = INAN, const int max = INAN) +{ + bool ok = true; + // Null field may be okay + if (field.empty()) { + if (required) { + ok = false; + } + } + // Otherwise we require a value + else { + int value = 0; + if (StrToInt(field, value)) { + // Range limits? + if ((min != INAN) && (value < min)) { + ok = false; + } + if ((max != INAN) && (value > max)) { + ok = false; + } + if (ok) { + fpaint.value = value; + fpaint.valid = true; + } + } else { + ok = false; + } + } + + FPA_TRACE("GetInt(\"%s\", %s, %d, %d)=%s value=%d/%s", field.c_str(), required ? "true" : "false", min, max, + ok ? "true" : "false", fpaint.value, fpaint.valid ? "true" : "false"); + return ok; +} + +// Get float value +static bool GetFloat( + FpaFloat& fpafloat, const std::string& field, const bool required, const double min = NAN, const double max = NAN) +{ + bool ok = true; + // Null field may be okay + if (field.empty()) { + if (required) { + ok = false; + } + } + // Otherwise we require a value + else { + double value = 0.0; + if (StrToFloat(field, value)) { + // Range limits? + if (std::isfinite(min) && (value < min)) { + ok = false; + } + if (std::isfinite(max) && (value > max)) { + ok = false; + } + if (ok) { + fpafloat.value = value; + fpafloat.valid = true; + } + } else { + ok = false; + } + } + + FPA_TRACE("GetFloat(\"%s\", %s, %g, %g)=%s value=%g/%s", field.c_str(), required ? "true" : "false", min, max, + ok ? "true" : "false", fpafloat.value, fpafloat.valid ? "true" : "false"); + return ok; +} + +template +static bool GetFloatArr(T& fpafloatx, const std::vector& fields, const int offs, const bool required, + const double min = NAN, const double max = NAN) +{ + bool ok = true; + bool valid = true; + static constexpr std::size_t N = std::tuple_size::value; + for (std::size_t ix = 0; ix < N; ix++) { + FpaFloat f; + ok = ok && GetFloat(f, fields[offs + ix], required, min, max); + valid = valid && f.valid; + fpafloatx.values[ix] = f.value; + } + fpafloatx.valid = valid; + FPA_TRACE("GetFloatArr<%d>(..., %s, %g, %g)=%s values=.../%s", (int)N, required ? "true" : "false", min, max, + ok ? "true" : "false", fpafloatx.valid ? "true" : "false"); + + // fields[offs].c_str(), + // fields[offs + 1].c_str(), fields[offs + 2].c_str(), , fpafloat3.values[0], fpafloat3.values[1], + // fpafloat3.values[2], fpafloat3.valid ? "true" : "false"); + return ok; +} + +static bool GetFloat3llh( + FpaFloat3& fpafloat3, const std::vector& fields, const int offs, const bool required) +{ + FpaFloat lat; + FpaFloat lon; + FpaFloat height; + const bool ok = GetFloat(lat, fields[offs], required, -90.0, 90.0) && + GetFloat(lon, fields[offs + 1], required, -180.0, 180.0) && + GetFloat(height, fields[offs + 2], required, -1000.0, 50000.0); + fpafloat3.valid = lat.valid && lon.valid && height.valid; + fpafloat3.values[0] = lat.value; + fpafloat3.values[1] = lon.value; + fpafloat3.values[2] = height.value; + FPA_TRACE("GetFloat3llh(\"%s\", \"%s\", \"%s\", %s)=%s values=%g/%g/%g/%s", fields[offs].c_str(), + fields[offs + 1].c_str(), fields[offs + 2].c_str(), required ? "true" : "false", ok ? "true" : "false", + fpafloat3.values[0], fpafloat3.values[1], fpafloat3.values[2], fpafloat3.valid ? "true" : "false"); + return ok; +} + +// Get GPS week/tow pair +static bool GetGpsTime( + FpaGpsTime& gps_time, const std::vector& fields, const int offs, const bool required = false) +{ + bool ok = + GetInt(gps_time.week, fields[offs], required, 0, 9999) && + GetFloat(gps_time.tow, fields[offs + 1], required, 0.0, 604800.0 - std::numeric_limits::epsilon()); + FPA_TRACE("GetGpsTime(\"%s\", \"%s\")=%s week=%d/%s tow=%.6f/%s", fields[offs].c_str(), fields[offs + 1].c_str(), + ok ? "true" : "false", gps_time.week.value, gps_time.week.valid ? "true" : "false", gps_time.tow.value, + gps_time.tow.valid ? "true" : "false"); + return ok; +} + +bool FpaGpsTime::operator==(const FpaGpsTime& rhs) const +{ + return (week.valid == rhs.week.valid) && (tow.valid == rhs.tow.valid) && (week.value == rhs.week.value) && + (std::fabs(tow.value - rhs.tow.value) < 1e-6); +} + +bool FpaGpsTime::operator!=(const FpaGpsTime& rhs) const +{ + return !(*this == rhs); +} + +bool FpaGpsTime::operator>(const FpaGpsTime& rhs) const +{ + return (week.valid == rhs.week.valid) && (tow.valid == rhs.tow.valid) && + ((week.value > rhs.week.value) || ((week.value == rhs.week.value) && (tow.value > rhs.tow.value))); +} + +bool FpaGpsTime::operator<(const FpaGpsTime& rhs) const +{ + return (week.valid == rhs.week.valid) && (tow.valid == rhs.tow.valid) && + ((week.value < rhs.week.value) || ((week.value == rhs.week.value) && (tow.value < rhs.tow.value))); +} + +bool FpaGpsTime::operator>=(const FpaGpsTime& rhs) const +{ + return (week.valid == rhs.week.valid) && (tow.valid == rhs.tow.valid) && + ((week.value > rhs.week.value) || ((week.value == rhs.week.value) && (tow.value >= rhs.tow.value))); +} + +bool FpaGpsTime::operator<=(const FpaGpsTime& rhs) const +{ + return (week.valid == rhs.week.valid) && (tow.valid == rhs.tow.valid) && + ((week.value < rhs.week.value) || ((week.value == rhs.week.value) && (tow.value <= rhs.tow.value))); +} + +static bool GetText(char* str, const std::size_t size, const std::string& field, const bool required = false) +{ + bool ok = true; + if (field.empty()) { + if (required) { + ok = false; + } else { + str[0] = '\0'; + } + } else if (field.size() > (size - 1)) { + ok = false; + } else { + std::memcpy(str, field.data(), field.size() + 1); + } + FPA_TRACE("GetText(..., %" PRIuMAX ", \"%s\", %s)=%s str=%s", size, field.c_str(), required ? "true" : "false", + ok ? "true" : "false", str); + return ok; +} + +// --------------------------------------------------------------------------------------------------------------------- + +bool FpaEoePayload::SetFromMsg(const uint8_t* msg, const std::size_t msg_size) +{ + // $FP,EOE,1,2322,309663.800000,FUSION*62 + // 0 1 2 + bool ok = false; + FpaParts m; + if (GetParts(m, "EOE", msg, msg_size) && (m.meta_.msg_version_ == 1) && (m.fields_.size() == 3)) { + ok = (GetGpsTime(gps_time, m.fields_, 0, false) && GetEpoch(epoch, m.fields_[2])); + } + FPA_TRACE("FpaEoePayload %s", ok ? "true" : "false"); + return ok; +} + +// --------------------------------------------------------------------------------------------------------------------- + +bool FpaGnssantPayload::SetFromMsg(const uint8_t* msg, const std::size_t msg_size) +{ + // $FP,GNSSANT,1,2234,305129.200151,short,off,0,open,on,28*65\r\n + // 0 1 2 3 4 5 6 7 + bool ok = false; + FpaParts m; + if (GetParts(m, "GNSSANT", msg, msg_size) && (m.meta_.msg_version_ == 1) && (m.fields_.size() == 8)) { + ok = (GetGpsTime(gps_time, m.fields_, 0, false) && GetAntState(gnss1_state, m.fields_[2]) && + GetAntPower(gnss1_power, m.fields_[3]) && GetInt(gnss1_age, m.fields_[4], false, 0) && + GetAntState(gnss2_state, m.fields_[5]) && GetAntPower(gnss2_power, m.fields_[6]) && + GetInt(gnss2_age, m.fields_[7], false, 0)); + } + FPA_TRACE("FpaGnssantPayload %s", ok ? "true" : "false"); + return ok; +} + +// --------------------------------------------------------------------------------------------------------------------- + +bool FpaGnsscorrPayload::SetFromMsg(const uint8_t* msg, const std::size_t msg_size) +{ + // $FP,GNSSCORR,1,2237,250035.999865,8,25,18,8,25,18,0.2,1.0,0.8,5.3,2,47.366986804,8.532965023,481.1094,7254*3F + // 0 1 2 3 4 5 6 7 8 9 10 11 12 13 14 15 16 + bool ok = false; + FpaParts m; + if (GetParts(m, "GNSSCORR", msg, msg_size) && (m.meta_.msg_version_ == 1) && (m.fields_.size() == 17)) { + ok = (GetGpsTime(gps_time, m.fields_, 0, false) && GetGnssFix(gnss1_fix, m.fields_[2]) && + GetInt(gnss1_nsig_l1, m.fields_[3], false, 0) && GetInt(gnss1_nsig_l2, m.fields_[4], false, 0) && + GetGnssFix(gnss2_fix, m.fields_[5]) && GetInt(gnss2_nsig_l1, m.fields_[6], false, 0) && + GetInt(gnss2_nsig_l2, m.fields_[7], false, 0) && GetFloat(corr_latency, m.fields_[8], false) && + GetFloat(corr_update_rate, m.fields_[9], false, 0.0) && + GetFloat(corr_data_rate, m.fields_[10], false, 0.0) && + GetFloat(corr_msg_rate, m.fields_[11], false, 0.0) && GetInt(sta_id, m.fields_[12], false, 0, 4095) && + GetFloat3llh(sta_llh, m.fields_, 13, false) && GetInt(sta_dist, m.fields_[16], false, 0)); + } + FPA_TRACE("FpaGnsscorrPayload %s", ok ? "true" : "false"); + return ok; +} + +// --------------------------------------------------------------------------------------------------------------------- + +bool FpaRawimuPayload::SetFromMsg(const uint8_t* msg, const std::size_t msg_size) +{ + // $FP,RAWIMU,1,2197,126191.777855,-0.199914,0.472851,9.917973,0.023436,0.007723,0.002131*34 + // 0 1 2 3 4 5 6 7 + bool ok = false; + FpaParts m; + if (GetParts(m, "RAWIMU", msg, msg_size) && (m.meta_.msg_version_ == 1) && (m.fields_.size() == 8)) { + ok = (GetGpsTime(gps_time, m.fields_, 0, false) && GetFloatArr(acc, m.fields_, 2, false) && + GetFloatArr(rot, m.fields_, 5, false)); + } + if (ok) { + which = Which::FP_A_RAWIMU; + } + FPA_TRACE("FpaRawimuPayload %s", ok ? "true" : "false"); + return ok; +} + +// --------------------------------------------------------------------------------------------------------------------- + +bool FpaCorrimuPayload::SetFromMsg(const uint8_t* msg, const std::size_t msg_size) +{ + // $FP,CORRIMU,1,2197,126191.777855,-0.195224,0.393969,9.869998,0.013342,-0.004620,-0.000728*7D + // 0 1 2 3 4 5 6 7 + bool ok = false; + FpaParts m; + if (GetParts(m, "CORRIMU", msg, msg_size) && (m.meta_.msg_version_ == 1) && (m.fields_.size() == 8)) { + ok = (GetGpsTime(gps_time, m.fields_, 0, false) && GetFloatArr(acc, m.fields_, 2, false) && + GetFloatArr(rot, m.fields_, 5, false)); + } + if (ok) { + which = Which::FP_A_CORRIMU; + } + FPA_TRACE("FpaCorrimuPayload %s", ok ? "true" : "false"); + return ok; +} + +// --------------------------------------------------------------------------------------------------------------------- + +bool FpaImubiasPayload::SetFromMsg(const uint8_t* msg, const std::size_t msg_size) +{ + // clang-format off + // $FP,IMUBIAS,1,2342,321247.000000,2,1,1,3,0.008914,0.019806,0.150631,0.027202,0.010599,0.011393,0.00001,0.00001,0.00001,0.00001,0.00001,0.00001*4C\r\n + // 0 1 2 3 4 5 6 7 8 9 10 11 12 13 14 15 16 17 + // clang-format on + bool ok = false; + FpaParts m; + if (GetParts(m, "IMUBIAS", msg, msg_size) && (m.meta_.msg_version_ == 1) && (m.fields_.size() == 18)) { + ok = (GetGpsTime(gps_time, m.fields_, 0, false) && GetMeasStatus(fusion_imu, m.fields_[2]) && + GetImuStatus(imu_status, m.fields_[3]) && GetImuNoise(imu_noise, m.fields_[4]) && + GetImuConv(imu_conv, m.fields_[5]) && GetFloatArr(bias_acc, m.fields_, 6, false) && + GetFloatArr(bias_gyr, m.fields_, 9, false) && GetFloatArr(bias_cov_acc, m.fields_, 12, false) && + GetFloatArr(bias_cov_gyr, m.fields_, 15, false)); + } + FPA_TRACE("FpaImubiasPayload %s", ok ? "true" : "false"); + return ok; +} + +// --------------------------------------------------------------------------------------------------------------------- + +bool FpaLlhPayload::SetFromMsg(const uint8_t* msg, const std::size_t msg_size) +{ + // clang-format off + // $FP,LLH,1,2231,227563.250000,47.392357470,8.448121451,473.5857,0.04533,0.03363,0.02884,0.00417,0.00086,-0.00136*62\r\n + // 0 1 2 3 4 5 6 7 8 9 10 + // clang-format on + bool ok = false; + FpaParts m; + if (GetParts(m, "LLH", msg, msg_size) && (m.meta_.msg_version_ == 1) && (m.fields_.size() == 11)) { + ok = (GetGpsTime(gps_time, m.fields_, 0, false) && GetFloat3llh(llh, m.fields_, 2, false) && + GetFloatArr(cov_enu, m.fields_, 5, false)); + } + FPA_TRACE("FpaLlhPayload %s", ok ? "true" : "false"); + return ok; +} + +// --------------------------------------------------------------------------------------------------------------------- + +bool FpaOdometryPayload::SetFromMsg(const uint8_t* msg, const std::size_t msg_size) +{ + bool ok = false; + FpaParts m; + if (GetParts(m, "ODOMETRY", msg, msg_size) && (m.meta_.msg_version_ == 2) && (m.fields_.size() == 42)) { + ok = (GetGpsTime(gps_time, m.fields_, 0, false) && GetFloatArr(pos, m.fields_, 2, false) && + GetFloatArr(orientation, m.fields_, 5, false) && GetFloatArr(vel, m.fields_, 9, false) && + GetFloatArr(rot, m.fields_, 12, false) && GetFloatArr(acc, m.fields_, 15, false) && + GetFusionStatusLegacy(fusion_status, m.fields_[18]) && + GetImuStatusLegacy(imu_bias_status, m.fields_[19]) && GetGnssFix(gnss1_fix, m.fields_[20]) && + GetGnssFix(gnss2_fix, m.fields_[21]) && GetWsStatusLegacy(wheelspeed_status, m.fields_[22]) && + GetFloatArr(pos_cov, m.fields_, 23, false) && GetFloatArr(orientation_cov, m.fields_, 29, false) && + GetFloatArr(vel_cov, m.fields_, 35, false)); + } + if (ok) { + which = Which::FP_A_ODOMETRY; + } + FPA_TRACE("FpaOdometryPayload %s", ok ? "true" : "false"); + return ok; +} + +// --------------------------------------------------------------------------------------------------------------------- + +bool FpaOdomenuPayload::SetFromMsg(const uint8_t* msg, const std::size_t msg_size) +{ + bool ok = false; + FpaParts m; + if (GetParts(m, "ODOMENU", msg, msg_size) && (m.meta_.msg_version_ == 1) && (m.fields_.size() == 41)) { + ok = (GetGpsTime(gps_time, m.fields_, 0, false) && GetFloatArr(pos, m.fields_, 2, false) && + GetFloatArr(orientation, m.fields_, 5, false) && GetFloatArr(vel, m.fields_, 9, false) && + GetFloatArr(rot, m.fields_, 12, false) && GetFloatArr(acc, m.fields_, 15, false) && + GetFusionStatusLegacy(fusion_status, m.fields_[18]) && + GetImuStatusLegacy(imu_bias_status, m.fields_[19]) && GetGnssFix(gnss1_fix, m.fields_[20]) && + GetGnssFix(gnss2_fix, m.fields_[21]) && GetWsStatusLegacy(wheelspeed_status, m.fields_[22]) && + GetFloatArr(pos_cov, m.fields_, 23, false) && GetFloatArr(orientation_cov, m.fields_, 29, false) && + GetFloatArr(vel_cov, m.fields_, 35, false)); + } + if (ok) { + which = Which::FP_A_ODOMENU; + } + FPA_TRACE("FpaOdomenuPayload %s", ok ? "true" : "false"); + return ok; +} + +// --------------------------------------------------------------------------------------------------------------------- + +bool FpaOdomshPayload::SetFromMsg(const uint8_t* msg, const std::size_t msg_size) +{ + bool ok = false; + FpaParts m; + if (GetParts(m, "ODOMSH", msg, msg_size) && (m.meta_.msg_version_ == 1) && (m.fields_.size() == 41)) { + ok = (GetGpsTime(gps_time, m.fields_, 0, false) && GetFloatArr(pos, m.fields_, 2, false) && + GetFloatArr(orientation, m.fields_, 5, false) && GetFloatArr(vel, m.fields_, 9, false) && + GetFloatArr(rot, m.fields_, 12, false) && GetFloatArr(acc, m.fields_, 15, false) && + GetFusionStatusLegacy(fusion_status, m.fields_[18]) && + GetImuStatusLegacy(imu_bias_status, m.fields_[19]) && GetGnssFix(gnss1_fix, m.fields_[20]) && + GetGnssFix(gnss2_fix, m.fields_[21]) && GetWsStatusLegacy(wheelspeed_status, m.fields_[22]) && + GetFloatArr(pos_cov, m.fields_, 23, false) && GetFloatArr(orientation_cov, m.fields_, 29, false) && + GetFloatArr(vel_cov, m.fields_, 35, false)); + } + if (ok) { + which = Which::FP_A_ODOMSH; + } + FPA_TRACE("FpaOdomshPayload %s", ok ? "true" : "false"); + return ok; +} + +// --------------------------------------------------------------------------------------------------------------------- + +bool FpaOdomstatusPayload::SetFromMsg(const uint8_t* msg, const std::size_t msg_size) +{ + // clang-format off + // $FP,ODOMSTATUS,1,2342,321241.350000,2,2,1,1,1,1,,0,,,,,,1,1,3,8,8,3,5,5,,0,6,,,,,,,,,,,,*24 + // 0 1 2 3 4 5 6 7 9 1516171819202122 2425 37 + // clang-format on + + bool ok = false; + FpaParts m; + if (GetParts(m, "ODOMSTATUS", msg, msg_size) && (m.meta_.msg_version_ == 1) && (m.fields_.size() == 38)) { + ok = (GetGpsTime(gps_time, m.fields_, 0, false) && GetInitStatus(init_status, m.fields_[2]) && + GetMeasStatus(fusion_imu, m.fields_[3]) && GetMeasStatus(fusion_gnss1, m.fields_[4]) && + GetMeasStatus(fusion_gnss2, m.fields_[5]) && GetMeasStatus(fusion_corr, m.fields_[6]) && + GetMeasStatus(fusion_cam1, m.fields_[7]) && GetMeasStatus(fusion_ws, m.fields_[9]) && + GetMeasStatus(fusion_markers, m.fields_[10]) && GetImuStatus(imu_status, m.fields_[15]) && + GetImuNoise(imu_noise, m.fields_[16]) && GetImuConv(imu_conv, m.fields_[17]) && + GetGnssStatus(gnss1_status, m.fields_[18]) && GetGnssStatus(gnss2_status, m.fields_[19]) && + GetBaselineStatus(baseline_status, m.fields_[20]) && GetCorrStatus(corr_status, m.fields_[21]) && + GetCamStatus(cam1_status, m.fields_[22]) && GetWsStatus(ws_status, m.fields_[24]) && + GetWsConv(ws_conv, m.fields_[25]) && GetMarkersStatus(markers_status, m.fields_[26]) && + GetMarkersConv(markers_conv, m.fields_[27])); + } + FPA_TRACE("FpaOdomstatusPayload %s", ok ? "true" : "false"); + return ok; +} + +// --------------------------------------------------------------------------------------------------------------------- + +bool FpaTextPayload::SetFromMsg(const uint8_t* msg, const std::size_t msg_size) +{ + // clang-format off + // $FP,TEXT,1,INFO,Fixposition AG - www.fixposition.com*09\r\n + // 0 1 + // clang-format on + bool ok = false; + FpaParts m; + if (GetParts(m, "TEXT", msg, msg_size) && (m.meta_.msg_version_ == 1) && (m.fields_.size() == 2)) { + ok = (GetTextLevel(level, m.fields_[0]) && GetText(text, sizeof(text), m.fields_[1], false)); + } + FPA_TRACE("FpaTextPayload %s", ok ? "true" : "false"); + return ok; +} + +// --------------------------------------------------------------------------------------------------------------------- + +bool FpaTfPayload::SetFromMsg(const uint8_t* msg, const std::size_t msg_size) +{ + // clang-format off + // $FP,TF,2,2233,315835.000000,VRTK,CAM,-0.00000,-0.00000,-0.00000,1.000000,0.000000,0.000000,0.000000*6B\r\n + // 0 1 2 3 4 5 6 7 8 9 10 + // clang-format on + bool ok = false; + FpaParts m; + if (GetParts(m, "TF", msg, msg_size) && (m.meta_.msg_version_ == 2) && (m.fields_.size() == 11)) { + ok = (GetGpsTime(gps_time, m.fields_, 0, false) && GetText(frame_a, sizeof(frame_a), m.fields_[2], true) && + GetText(frame_b, sizeof(frame_b), m.fields_[3], true) && GetFloatArr(translation, m.fields_, 4, true) && + GetFloatArr(orientation, m.fields_, 7, true)); + } + FPA_TRACE("FpaTfPayload %s", ok ? "true" : "false"); + return ok; +} + +// --------------------------------------------------------------------------------------------------------------------- + +bool FpaTpPayload::SetFromMsg(const uint8_t* msg, const std::size_t msg_size) +{ + // clang-format off + // $FP,TP,1,GNSS1,UTC,USNO,195391,0.000000000000,18*4F\r\n + // 0 1 2 3 4 5 + // clang-format on + bool ok = false; + FpaParts m; + if (GetParts(m, "TP", msg, msg_size) && (m.meta_.msg_version_ == 1) && (m.fields_.size() == 6)) { + ok = (GetText(tp_name, sizeof(tp_name), m.fields_[0], true) && GetTimebase(timebase, m.fields_[1]) && + GetTimeref(timeref, m.fields_[2]) && GetInt(tp_tow_sec, m.fields_[3], false, 0) && + GetFloat(tp_tow_psec, m.fields_[4], false, 0.0, 0.999999999) && + GetInt(gps_leaps, m.fields_[5], false, 0)); + } + FPA_TRACE("FpaTpPayload %s", ok ? "true" : "false"); + return ok; +} + +/* ****************************************************************************************************************** */ +} // namespace fpa +} // namespace parser +} // namespace common +} // namespace fpsdk diff --git a/fpsdk_common/src/parser/fpb.cpp b/fpsdk_common/src/parser/fpb.cpp new file mode 100644 index 0000000..3323ff4 --- /dev/null +++ b/fpsdk_common/src/parser/fpb.cpp @@ -0,0 +1,191 @@ +/** + * \verbatim + * ___ ___ + * \ \ / / + * \ \/ / Copyright (c) Fixposition AG (www.fixposition.com) and contributors + * / /\ \ License: see the LICENSE file + * /__/ \__\ + * + * Based on work by flipflip (https://github.com/phkehl) + * \endverbatim + * + * @file + * @brief Fixposition SDK: Parser FP_B routines and types + */ + +/* LIBC/STL */ +#include +#include +#include +#include + +/* EXTERNAL */ + +/* PACKAGE */ +#include "fpsdk_common/parser/crc.hpp" +#include "fpsdk_common/parser/fpb.hpp" +#include "fpsdk_common/parser/types.hpp" + +namespace fpsdk { +namespace common { +namespace parser { +namespace fpb { +/* ****************************************************************************************************************** */ + +// Lookup table entry +struct MsgInfo +{ + uint16_t msg_id; + const char* name; +}; + +// clang-format off +// @fp_codegen_begin{FPSDK_COMMON_PARSER_FPB_MSGINFO} +static constexpr std::array MSG_INFO = +{{ + { FP_B_GNSSSTATUS_MSGID, FP_B_GNSSSTATUS_STRID }, + { FP_B_SYSTEMSTATUS_MSGID, FP_B_SYSTEMSTATUS_STRID }, + { FP_B_MEASUREMENTS_MSGID, FP_B_MEASUREMENTS_STRID }, + { FP_B_VERSION_MSGID, FP_B_VERSION_STRID }, + { FP_B_UNITTEST1_MSGID, FP_B_UNITTEST1_STRID }, + { FP_B_UNITTEST2_MSGID, FP_B_UNITTEST2_STRID }, +}}; +// @fp_codegen_end{FPSDK_COMMON_PARSER_FPB_MSGINFO} +// clang-format on + +bool FpbGetMessageName(char* name, const std::size_t size, const uint8_t* msg, const std::size_t msg_size) +{ + // Check arguments + if ((name == NULL) || (size == 0)) { + return false; + } + name[0] = '\0'; + + if ((msg == NULL) || (msg_size < FP_B_FRAME_SIZE)) { + return false; + } + + const uint16_t msg_id = FpbMsgId(msg); + + // Try the message name lookup table + for (auto& info : MSG_INFO) { + if (info.msg_id == msg_id) { + return std::snprintf(name, size, "%s", info.name) < (int)size; + } + } + + // If that failed, too, stringify the message ID + return std::snprintf(name, size, "FP_B-MSG%05" PRIu16, msg_id) < (int)size; +} + +// --------------------------------------------------------------------------------------------------------------------- + +bool FpbMakeMessage(std::vector& msg, const uint16_t msg_id, const uint16_t msg_time, const uint8_t* payload, + const std::size_t payload_size) +{ + if (((payload == NULL) && (payload_size > 0)) || (payload_size > (MAX_FP_B_SIZE - FP_B_FRAME_SIZE))) { + return false; + } + + const uint16_t payload_size_u = payload_size; + const std::size_t msg_size = payload_size_u + FP_B_FRAME_SIZE; + + msg.resize(msg_size); + msg[0] = FP_B_SYNC_1; + msg[1] = FP_B_SYNC_2; + msg[2] = (msg_id & 0xff); + msg[3] = (msg_id >> 8); + msg[4] = (payload_size_u & 0xff); + msg[5] = (payload_size_u >> 8); + msg[6] = (msg_time & 0xff); + msg[7] = (msg_time >> 8); + if ((payload != NULL) && (payload_size_u > 0)) { + std::memcpy(&msg[FP_B_HEAD_SIZE], payload, payload_size_u); + } + const uint32_t crc = crc::Crc32fpb(&msg[0], msg_size - sizeof(crc)); + // clang-format off + msg[msg_size - 4] = ( crc & 0xff); + msg[msg_size - 3] = ((crc >> 8) & 0xff); + msg[msg_size - 2] = ((crc >> 16) & 0xff); + msg[msg_size - 1] = ((crc >> 24) & 0xff); + // clang-format on + return true; +} + +bool FpbMakeMessage( + std::vector& msg, const uint16_t msg_id, const uint16_t msg_time, const std::vector& payload) +{ + return FpbMakeMessage(msg, msg_id, msg_time, payload.data(), payload.size()); +} + +// --------------------------------------------------------------------------------------------------------------------- + +static std::size_t StrFpbMeasurements( + char* info, const std::size_t size, const uint8_t* msg, const std::size_t msg_size) +{ + if (msg_size < FP_B_MEASUREMENTS_HEAD_SIZE) { + return 0; + } + std::size_t num = 0; + FpbMeasurementsHead head; + std::memcpy(&head, &msg[FP_B_HEAD_SIZE], sizeof(head)); + num += std::snprintf(&info[num], size - num, " v%" PRIu8, head.version); + if (head.version == FP_B_MEASUREMENTS_V1) { + num += std::snprintf(&info[num], size - num, " [%" PRIu8 "]", head.num_meas); + for (std::size_t ix = 0; (ix < head.num_meas) && (num < (size - 50)); ix++) { + FpbMeasurementsMeas meas; + std::memcpy(&meas, &msg[FP_B_HEAD_SIZE + sizeof(head) + (ix * sizeof(meas))], sizeof(meas)); + num += std::snprintf(&info[num], size - num, " / %" PRIu8 " %" PRIu8 " %" PRIu8 " %" PRIu16 " %" PRIu32, + meas.meas_type, meas.meas_loc, meas.timestamp_type, meas.gps_wno, meas.gps_tow); + if (meas.meas_x_valid) { + num += std::snprintf(&info[num], size - num, " %" PRIi32, meas.meas_x); + } else { + num += std::snprintf(&info[num], size - num, " >"); + } + if (meas.meas_y_valid) { + num += std::snprintf(&info[num], size - num, " %" PRIi32, meas.meas_y); + } else { + num += std::snprintf(&info[num], size - num, " >"); + } + if (meas.meas_z_valid) { + num += std::snprintf(&info[num], size - num, " %" PRIi32, meas.meas_z); + } else { + num += std::snprintf(&info[num], size - num, " >"); + } + } + } + return num; +} + +// --------------------------------------------------------------------------------------------------------------------- + +bool FpbGetMessageInfo(char* info, const std::size_t size, const uint8_t* msg, const std::size_t msg_size) +{ + if ((info == NULL) || (size == 0)) { + return false; + } + + if ((msg == NULL) || (msg_size < (FP_B_HEAD_SIZE + 2))) { + info[0] = '\0'; + return false; + } + std::size_t len = 0; + + // Common stringification + len += snprintf(&info[len], size - len, "%04" PRIx16 "@%" PRIu16, FpbMsgId(msg), FpbMsgTime(msg)); + + // Specific stringification for some messages + switch (FpbMsgId(msg)) { + case FP_B_MEASUREMENTS_MSGID: + len += StrFpbMeasurements(&info[len], size - len, msg, msg_size); + break; + } + + return (len > 0) && (len < size); +} + +/* ****************************************************************************************************************** */ +} // namespace fpb +} // namespace parser +} // namespace common +} // namespace fpsdk diff --git a/fpsdk_common/src/parser/nmea.cpp b/fpsdk_common/src/parser/nmea.cpp new file mode 100644 index 0000000..78f702b --- /dev/null +++ b/fpsdk_common/src/parser/nmea.cpp @@ -0,0 +1,1094 @@ +/** + * \verbatim + * ___ ___ + * \ \ / / + * \ \/ / Copyright (c) Fixposition AG (www.fixposition.com) and contributors + * / /\ \ License: see the LICENSE file + * /__/ \__\ + * + * Based on work by flipflip (https://github.com/phkehl) + * \endverbatim + * + * @file + * @brief Fixposition SDK: Parser NMEA routines and types + */ + +/* LIBC/STL */ +#include +#include +#include +#include +#include +#include +#include + +/* EXTERNAL */ + +/* PACKAGE */ +#include "fpsdk_common/math.hpp" +#include "fpsdk_common/parser/nmea.hpp" +#include "fpsdk_common/types.hpp" + +namespace fpsdk { +namespace common { +namespace parser { +namespace nmea { +/* ****************************************************************************************************************** */ + +bool NmeaGetMessageMeta(NmeaMessageMeta& meta, const uint8_t* msg, const std::size_t msg_size) +{ + if ((msg == NULL) || (msg_size < 10)) { + return false; + } + meta.payload_ix0_ = 0; + meta.payload_ix1_ = 0; + + // 012345678901234567890123456789 + // $TTF*xx\r\n" + // $GNGGA,...,...,...*xx\r\n + // $PUBX,nn,...,...,...*xx\r\n + // $FP,ODOMETRY,n,...,...,...*xx\r\n + + // Talker ID + std::size_t offs = 0; + if (msg[1] == 'P') // Proprietary + { + meta.talker_[0] = 'P'; + meta.talker_[1] = '\0'; + offs = 2; + } else { + meta.talker_[0] = msg[1]; + meta.talker_[1] = msg[2]; + meta.talker_[2] = '\0'; + offs = 3; + } + + // Sentence formatter + std::size_t comma_ix = 0; + for (std::size_t ix = offs; (ix < (msg_size - 4)) && (ix < (sizeof(meta.formatter_) - 1 + offs)); ix++) { + if ((msg[ix] == ',') || (msg[ix] == '*')) { + comma_ix = ix; + break; + } + } + if (comma_ix <= 0) { + meta.formatter_[0] = '\0'; + return false; + } + + std::size_t i_ix; + std::size_t o_ix; + const std::size_t max_o = sizeof(meta.formatter_) - 1; + for (i_ix = offs, o_ix = 0; (i_ix < comma_ix) && (o_ix < max_o); i_ix++, o_ix++) { + meta.formatter_[o_ix] = msg[i_ix]; + } + meta.formatter_[o_ix] = '\0'; + + // No payload + if (msg[comma_ix] == '*') { + meta.payload_ix0_ = 0; + meta.payload_ix1_ = 0; + return true; + } + + meta.payload_ix0_ = comma_ix + 1; + meta.payload_ix1_ = msg_size - 5 - 1; // "*XX\r\n" + + return true; +} + +// --------------------------------------------------------------------------------------------------------------------- + +bool NmeaGetMessageName(char* name, const std::size_t size, const uint8_t* msg, const std::size_t msg_size) +{ + if ((name == NULL) || (size < 1)) { + return false; + } + name[0] = '\0'; + + NmeaMessageMeta meta; + if (!NmeaGetMessageMeta(meta, msg, msg_size)) { + return false; + } + + // u-blox proprietary + if ((meta.talker_[0] == 'P') && (meta.formatter_[0] == 'U') && (meta.formatter_[1] == 'B') && + (meta.formatter_[2] == 'X') && (meta.formatter_[3] == '\0')) { + const char* pubx = NULL; + const char c1 = msg[meta.payload_ix0_]; + const char c2 = msg[meta.payload_ix0_ + 1]; + // clang-format off + if ( (c1 == '4') && (c2 == '1') ) { pubx = "CONFIG"; } + else if ( (c1 == '0') && (c2 == '0') ) { pubx = "POSITION"; } + else if ( (c1 == '4') && (c2 == '0') ) { pubx = "RATE"; } + else if ( (c1 == '0') && (c2 == '3') ) { pubx = "SVSTATUS"; } + else if ( (c1 == '0') && (c2 == '4') ) { pubx = "TIME"; } // clang-format on + else { + return std::snprintf(name, size, "NMEA-PUBX-%c%c", c1, c2) < (int)size; + } + return std::snprintf(name, size, "NMEA-PUBX-%s", pubx) < (int)size; + } + // Standard NMEA, incl. other proprietary ("P" talker ID) + else { + return std::snprintf(name, size, "NMEA-%s-%s", meta.talker_[0] != '\0' ? meta.talker_ : "?", + meta.formatter_[0] != '\0' ? meta.formatter_ : "?") < (int)size; + } + + return false; +} + +// --------------------------------------------------------------------------------------------------------------------- + +bool NmeaGetMessageInfo(char* info, const std::size_t size, const uint8_t* msg, const std::size_t msg_size) +{ + if ((info == NULL) || (size < 1)) { + return false; + } + std::size_t len = 0; + NmeaMessageMeta meta; + if (NmeaGetMessageMeta(meta, msg, msg_size)) { + char fmt[20]; + snprintf(fmt, sizeof(fmt), "%%.%ds", meta.payload_ix1_ - meta.payload_ix0_ + 1); + len += snprintf(info, size, fmt, (const char*)&msg[meta.payload_ix0_]); + } + return (len > 0) && (len < size); +} + +// --------------------------------------------------------------------------------------------------------------------- + +NmeaCoordinates::NmeaCoordinates(const double degs, const int digits) +{ + sign_ = (degs >= 0.0); + const double degs_abs = std::abs(degs); + deg_ = (int)degs_abs; + const double frac_deg = degs_abs - (double)deg_; + min_ = math::RoundToFracDigits(frac_deg * 60.0, digits); +} + +// --------------------------------------------------------------------------------------------------------------------- + +/*static*/ const NmeaVersion NmeaVersion::V410 = { 1, 32, 33, 64, 65, 96, 1, 36, 1, 63, -1, -1 }; +/*static*/ const NmeaVersion NmeaVersion::V410_UBX_EXT = { 1, 32, 33, 64, 65, 96, 1, 36, 1, 63, 193, 202 }; +/*static*/ const NmeaVersion NmeaVersion::V411 = { 1, 32, 33, 64, 65, 96, 1, 36, 1, 63, 1, 10 }; + +// --------------------------------------------------------------------------------------------------------------------- + +bool NmeaTime::operator==(const NmeaTime& rhs) const +{ + return (valid == rhs.valid) && (hours == rhs.hours) && (mins == rhs.mins) && (std::abs(secs - rhs.secs) < 1e-9); +} + +bool NmeaTime::operator!=(const NmeaTime& rhs) const +{ + return !(*this == rhs); +} + +bool NmeaDate::operator==(const NmeaDate& rhs) const +{ + return (valid == rhs.valid) && (years == rhs.years) && (months == rhs.months) && (days == rhs.days); +} + +bool NmeaDate::operator!=(const NmeaDate& rhs) const +{ + return !(*this == rhs); +} + +// Parse float +static bool StrToFloat(const std::string& str, double& value) +{ + if (str.empty() || (std::isspace(str[0]) != 0)) { + return false; + } + + double value_tmp = 0.0f; + int num = 0; + int count = std::sscanf(str.data(), "%lf%n", &value_tmp, &num); + + if ((count == 1) && ((std::size_t)num == str.size()) && std::isfinite(value_tmp)) { + value = value_tmp; + return true; + } else { + return false; + } +} + +// Parse decimal (!) integer +static bool StrToInt(const std::string& str, int32_t& value) +{ + // No empty string, no leading whitespace + if (str.empty() || (std::isspace(str[0]) != 0)) { + return false; + } + + // Parse + int64_t value_tmp = 0; + int num = 0; + int count = std::sscanf(str.data(), "%" SCNd64 "%n", &value_tmp, &num); // *decimal* integer, so SCNd, not SCNi + // Number of values found must be 1 and the entire string must have been used (no trailing stuff) + if ((count == 1) && ((std::size_t)num == str.size()) && (value_tmp >= INT32_MIN) && (value_tmp <= INT32_MAX)) { + value = value_tmp; + return true; + } else { + return false; + } +} + +// --------------------------------------------------------------------------------------------------------------------- +// Various helpers for the SetFromMsg() NMEA decoding functions + +// Debug prints, for development +#if 0 +# define NMEA_TRACE(fmt, ...) fprintf(stderr, fmt "\n", ##__VA_ARGS__) +#else +# define NMEA_TRACE(fmt, ...) /* nothing */ +#endif + +// Split NMEA sentence (message) into its meta data and the payload fields +struct NmeaParts +{ + NmeaMessageMeta meta_; + std::vector fields_; +}; + +static bool GetParts(NmeaParts& parts, const char* formatter, const uint8_t* msg, const std::size_t msg_size) +{ + bool ok = true; + + if (!NmeaGetMessageMeta(parts.meta_, msg, msg_size) || (parts.meta_.payload_ix0_ <= 0) || + (parts.meta_.payload_ix1_ <= 0)) { + ok = false; + } else { + if (std::strcmp(parts.meta_.formatter_, formatter) != 0) { + ok = false; + } + + std::string payload((const char*)&msg[parts.meta_.payload_ix0_], + (const char*)&msg[parts.meta_.payload_ix0_] + (parts.meta_.payload_ix1_ - parts.meta_.payload_ix0_ + 1)); + + NMEA_TRACE("GetParts(...) talker=%s formatter=%s payload=%s ix0=%d ix1=%d size=%d", parts.meta_.talker_, + parts.meta_.formatter_, payload.c_str(), parts.meta_.payload_ix0_, parts.meta_.payload_ix1_, msg_size); + + std::size_t pos = 0; + while ((pos = payload.find(",")) != std::string::npos) { + std::string part = payload.substr(0, pos); + payload.erase(0, pos + 1); + parts.fields_.push_back(part); + } + parts.fields_.push_back(payload); + } + + NMEA_TRACE( + "GetParts(..., \"%s\", ..., ...)=%s #fields=%d", formatter, ok ? "true" : "false", (int)parts.fields_.size()); + return ok; +} + +// Get talker ID +bool GetTalker(NmeaTalkerId& talker, const char* talkerstr) +{ + bool ok = true; + if (talkerstr[0] == 'P') { + talker = NmeaTalkerId::PROPRIETARY; + } else if (talkerstr[0] == 'G') { + switch ((NmeaTalkerId)talkerstr[1]) { // clang-format off + case NmeaTalkerId::GPS_SBAS: talker = NmeaTalkerId::GPS_SBAS; break; + case NmeaTalkerId::GLO: talker = NmeaTalkerId::GLO; break; + case NmeaTalkerId::GAL: talker = NmeaTalkerId::GAL; break; + case NmeaTalkerId::BDS: talker = NmeaTalkerId::BDS; break; + case NmeaTalkerId::NAVIC: talker = NmeaTalkerId::NAVIC; break; + case NmeaTalkerId::QZSS: talker = NmeaTalkerId::QZSS; break; + case NmeaTalkerId::GNSS: talker = NmeaTalkerId::GNSS; break; + case NmeaTalkerId::UNSPECIFIED: + case NmeaTalkerId::PROPRIETARY: ok = false; break; + } // clang-format on + } else { + ok = false; + } + NMEA_TRACE("GetTalker(\"%s\")=%s talker=%c", talkerstr, ok ? "true" : "false", types::EnumToVal(talker)); + return ok; +} + +// Get position, and optionally height +static bool GetLlh(NmeaLlh& llh, const std::vector& fields, const int lat_ix, const int lon_ix, + const int alt_ix, const int sep_ix, const bool required) +{ + bool ok = true; + + // Lat/lon + if (fields[lat_ix].empty() || fields[lon_ix].empty()) { + if (required) { + ok = false; + } + } else { + double latval = 0.0; + double lonval = 0.0; + if (StrToFloat(fields[lat_ix], latval) && !fields[lat_ix + 1].empty() && (latval >= 0.0) && + (latval <= 9000.0) && StrToFloat(fields[lon_ix], lonval) && !fields[lon_ix + 1].empty() && + (lonval >= 0.0) && (lonval <= 18000.0)) { + const double ilat = std::floor(latval / 100.0); + latval -= ilat * 100.0; + llh.lat = ilat + (latval / 60.0); + if (fields[lat_ix + 1] == "S") { + llh.lat = -llh.lat; + } + const double ilon = std::floor(lonval / 100.0); + lonval -= ilon * 100.0; + llh.lon = ilon + (lonval / 60.0); + if (fields[lon_ix + 1] == "W") { + llh.lon = -llh.lon; + } + llh.latlon_valid = true; + } else { + ok = false; + } + } + + // Optional height + if ((alt_ix >= 0) && (sep_ix >= 0)) { + if (fields[alt_ix].empty()) { + if (required) { + ok = false; + } + } else { + double heightval = 0.0; + double sepval = 0.0; + if (StrToFloat(fields[alt_ix], heightval) && (fields[alt_ix + 1] == "M") && + (fields[sep_ix].empty() || (StrToFloat(fields[sep_ix], sepval) && (fields[sep_ix + 1] == "M")))) { + // Contrary to the NMEA standard we'll allow sep (fields[10]) to be empty and assume that height + // (fields[9]) is ellipsoidal instead of mean sea level + llh.height = heightval + sepval; + llh.height_valid = true; + } else { + ok = false; + } + } + } + + NMEA_TRACE("GetLlh(%d=\"%s\", %d=\"%s\", %d=\"%s\", %d=\"%s\", %s)=%s ll=%g/%g/%s h=%g/%s", lat_ix, + lat_ix >= 0 ? fields[lat_ix].c_str() : "", lon_ix, lon_ix >= 0 ? fields[lon_ix].c_str() : "", alt_ix, + alt_ix >= 0 ? fields[alt_ix].c_str() : "", sep_ix, sep_ix >= 0 ? fields[sep_ix].c_str() : "", + required ? "true" : "false", ok ? "true" : "false", llh.lat, llh.lon, llh.latlon_valid ? "true" : "false", + llh.height, llh.height_valid ? "true" : "false"); + return ok; +} + +// Get time, with basic range checks, may be null +static bool GetTime(NmeaTime& time, const std::string& field) +{ + bool ok = true; + if (!field.empty()) { + double timeval = 0.0; + if (StrToFloat(field, timeval)) { + time.valid = !((timeval < 0.0) || (timeval > 235962.0)); // 00:00:00 .. 23:59:61.9999 + time.hours = std::floor(timeval / 10000.0); + timeval -= time.hours * 10000; + time.mins = std::floor(timeval / 100.0); + timeval -= time.mins * 100.0; + time.secs = timeval; + return true; + } else { + ok = false; + } + } + NMEA_TRACE("GetTime(\"%s\")=%s time=%d/%d/%g/%s", field.c_str(), ok ? "true" : "false", time.hours, time.mins, + time.secs, time.valid ? "true" : "false"); + return ok; +} + +// Get date (DDMMYY format), with basic range checks, may be null +static bool GetDateDdMmYy(NmeaDate& date, const std::string& field) +{ + bool ok = true; + if (!field.empty()) { + int dateval = 0; + if (StrToInt(field, dateval)) { + date.years = dateval % 100; + date.years += (date.years >= 80 ? 1900 : 2000); + date.months = (dateval / 100) % 100; + date.days = (dateval / 10000) % 100; + date.valid = ((date.years >= 2001) && (date.years <= 2099)); // 2001-01-01 ... 2099-12-31 + } else { + ok = false; + } + } + NMEA_TRACE("GetDateDdMmYy(\"%s\")=%s date=%d/%d/%d/%s", field.c_str(), ok ? "true" : "false", date.years, + date.months, date.days, date.valid ? "true" : "false"); + return ok; +} + +#if 0 +// Get date (YYYYMMDD format), with basic range checks, may be null +static bool GetDateYyyyMmDd(NmeaDate& date, const std::string& field) { + bool ok = true; + if (!field.empty()) { + int dateval = 0; + if (StrToInt(field, dateval)) { + // During coldstart the receiver reports 19800105... + date.days = dateval % 100; + date.months = (dateval / 100) % 100; + date.years = (dateval / 10000) % 10000; + date.valid = ((date.years >= 2001) && (date.years <= 2099)); // 2001-01-01 ... 2099-12-31 + } else { + ok = false; + } + } + NMEA_TRACE("GetDateYyyyMmDd(\"%s\")=%s date=%d/%d/%d/%s", field.c_str(), ok ? "true" : "false", date.years, + date.months, date.days, date.valid ? "true" : "false"); + return ok; +} +#endif + +// Get satellite +static bool GetSat(NmeaSat& sat, const std::string& field, const NmeaSystemId system, const bool required) +{ + bool ok = true; + + if (field.empty()) { + if (required) { + ok = false; + } + } else { + sat.system = system; + if (StrToInt(field, sat.svid) && sat.svid >= 0) { // @todo more validity checks per system? + sat.valid = true; + } else { + ok = false; + } + } + NMEA_TRACE("GetSat(\"%s\")=%s svid=%d/%c/%s", field.c_str(), ok ? "true" : "false", sat.svid, + types::EnumToVal(sat.system), sat.valid ? "true" : "false"); + return ok; +} + +// Get GGA quality flag +static bool GetQualityGga(NmeaQualityGga& quality, const std::string& field) +{ + bool ok = true; + if (!field.empty()) { + switch ((NmeaQualityGga)field[0]) { // clang-format off + case NmeaQualityGga::NOFIX: quality = NmeaQualityGga::NOFIX; break; + case NmeaQualityGga::SPP: quality = NmeaQualityGga::SPP; break; + case NmeaQualityGga::DGNSS: quality = NmeaQualityGga::DGNSS; break; + case NmeaQualityGga::PPS: quality = NmeaQualityGga::PPS; break; + case NmeaQualityGga::RTK_FIXED: quality = NmeaQualityGga::RTK_FIXED; break; + case NmeaQualityGga::RTK_FLOAT: quality = NmeaQualityGga::RTK_FLOAT; break; + case NmeaQualityGga::ESTIMATED: quality = NmeaQualityGga::ESTIMATED; break; + case NmeaQualityGga::MANUAL: quality = NmeaQualityGga::MANUAL; break; + case NmeaQualityGga::SIM: quality = NmeaQualityGga::SIM; break; + case NmeaQualityGga::UNSPECIFIED: ok = false; break; + } // clang-format on + } else { + ok = false; + } + NMEA_TRACE("GetQualityGga(\"%s\")=%s quality=%c", field.c_str(), ok ? "true" : "false", types::EnumToVal(quality)); + return ok; +} + +// Get GLL/RMC status flag +static bool GetStatusGllRmc(NmeaStatusGllRmc& status, const std::string& field) +{ + bool ok = true; + if (!field.empty()) { + switch ((NmeaStatusGllRmc)field[0]) { // clang-format off + case NmeaStatusGllRmc::INVALID: status = NmeaStatusGllRmc::INVALID; break; + case NmeaStatusGllRmc::VALID: status = NmeaStatusGllRmc::VALID; break; + case NmeaStatusGllRmc::UNSPECIFIED: ok = false; break; + } // clang-format on + } else { + ok = false; + } + NMEA_TRACE("GetStatusGllRmc(\"%s\")=%s status=%c", field.c_str(), ok ? "true" : "false", types::EnumToVal(status)); + return ok; +} + +// Get GLL/VTG mode flag +static bool GetModeGllVtg(NmeaModeGllVtg& mode, const std::string& field) +{ + bool ok = true; + if (!field.empty()) { + switch ((NmeaModeGllVtg)field[0]) { // clang-format off + case NmeaModeGllVtg::INVALID: mode = NmeaModeGllVtg::INVALID; break; + case NmeaModeGllVtg::AUTONOMOUS: mode = NmeaModeGllVtg::AUTONOMOUS; break; + case NmeaModeGllVtg::DGNSS: mode = NmeaModeGllVtg::DGNSS; break; + case NmeaModeGllVtg::ESTIMATED: mode = NmeaModeGllVtg::ESTIMATED; break; + case NmeaModeGllVtg::MANUAL: mode = NmeaModeGllVtg::MANUAL; break; + case NmeaModeGllVtg::SIM: mode = NmeaModeGllVtg::SIM; break; + case NmeaModeGllVtg::UNSPECIFIED: ok = false; break; + } // clang-format on + } else { + ok = false; + } + NMEA_TRACE("GetModeGllVtg(\"%s\")=%s mode=%c", field.c_str(), ok ? "true" : "false", types::EnumToVal(mode)); + return ok; +} + +// Get RMC/GNS mode flag +static bool GetModeRmcGns(NmeaModeRmcGns& mode, const std::string& field) +{ + bool ok = true; + if (!field.empty()) { + switch ((NmeaModeRmcGns)field[0]) { // clang-format off + case NmeaModeRmcGns::INVALID: mode = NmeaModeRmcGns::INVALID; break; + case NmeaModeRmcGns::AUTONOMOUS: mode = NmeaModeRmcGns::AUTONOMOUS; break; + case NmeaModeRmcGns::DGNSS: mode = NmeaModeRmcGns::DGNSS; break; + case NmeaModeRmcGns::ESTIMATED: mode = NmeaModeRmcGns::ESTIMATED; break; + case NmeaModeRmcGns::RTK_FIXED: mode = NmeaModeRmcGns::RTK_FIXED; break; + case NmeaModeRmcGns::RTK_FLOAT: mode = NmeaModeRmcGns::RTK_FLOAT; break; + case NmeaModeRmcGns::PRECISE: mode = NmeaModeRmcGns::PRECISE; break; + case NmeaModeRmcGns::MANUAL: mode = NmeaModeRmcGns::MANUAL; break; + case NmeaModeRmcGns::SIM: mode = NmeaModeRmcGns::SIM; break; + case NmeaModeRmcGns::UNSPECIFIED: ok = false; break; + } // clang-format on + } else { + ok = false; + } + NMEA_TRACE("GetModeRmcGns(\"%s\")=%s mode=%c", field.c_str(), ok ? "true" : "false", types::EnumToVal(mode)); + return ok; +} + +// Get RMC status flag +static bool GetNavStatusRmc(NmeaNavStatusRmc& navstatus, const std::string& field) +{ + bool ok = true; + if (!field.empty()) { + switch ((NmeaNavStatusRmc)field[0]) { // clang-format off + case NmeaNavStatusRmc::SAFE: navstatus = NmeaNavStatusRmc::SAFE; break; + case NmeaNavStatusRmc::CAUTION: navstatus = NmeaNavStatusRmc::CAUTION; break; + case NmeaNavStatusRmc::UNSAFE: navstatus = NmeaNavStatusRmc::UNSAFE; break; + case NmeaNavStatusRmc::NA: navstatus = NmeaNavStatusRmc::NA; break; + case NmeaNavStatusRmc::UNSPECIFIED: ok = false; break; + } // clang-format on + } else { + ok = false; + } + NMEA_TRACE( + "GetNavStatusRmc(\"%s\")=%s navstatus=%c", field.c_str(), ok ? "true" : "false", types::EnumToVal(navstatus)); + return ok; +} + +// Get GNS operation mode +static bool GetOpModeGsa(NmeaOpModeGsa& opmode, const std::string& field) +{ + bool ok = true; + if (!field.empty()) { + switch ((NmeaOpModeGsa)field[0]) { // clang-format off + case NmeaOpModeGsa::MANUAL: opmode = NmeaOpModeGsa::MANUAL; break; + case NmeaOpModeGsa::AUTO: opmode = NmeaOpModeGsa::AUTO; break; + case NmeaOpModeGsa::UNSPECIFIED: ok = false; break; + } // clang-format on + } else { + ok = false; + } + NMEA_TRACE("GetOpModeGsa(\"%s\")=%s opmode=%c", field.c_str(), ok ? "true" : "false", types::EnumToVal(opmode)); + return ok; +} + +// Get GNS operation mode +static bool GetNavModeGsa(NmeaNavModeGsa& navmode, const std::string& field) +{ + bool ok = true; + if (!field.empty()) { + switch ((NmeaNavModeGsa)field[0]) { // clang-format off + case NmeaNavModeGsa::NOFIX: navmode = NmeaNavModeGsa::NOFIX; break; + case NmeaNavModeGsa::FIX2D: navmode = NmeaNavModeGsa::FIX2D; break; + case NmeaNavModeGsa::FIX3D: navmode = NmeaNavModeGsa::FIX3D; break; + case NmeaNavModeGsa::UNSPECIFIED: ok = false; break; + } // clang-format on + } else { + ok = false; + } + NMEA_TRACE("GetNavModeGsa(\"%s\")=%s navmode=%c", field.c_str(), ok ? "true" : "false", types::EnumToVal(navmode)); + return ok; +} + +// Get (GSA) system ID +static bool GetSystemId(NmeaSystemId& system, const std::string& field) +{ + bool ok = true; + if (!field.empty()) { + switch ((NmeaSystemId)field[0]) { // clang-format off + case NmeaSystemId::GPS_SBAS: system = NmeaSystemId::GPS_SBAS; break; + case NmeaSystemId::GLO: system = NmeaSystemId::GLO; break; + case NmeaSystemId::GAL: system = NmeaSystemId::GAL; break; + case NmeaSystemId::BDS: system = NmeaSystemId::BDS; break; + case NmeaSystemId::QZSS: system = NmeaSystemId::QZSS; break; + case NmeaSystemId::NAVIC: system = NmeaSystemId::NAVIC; break; + case NmeaSystemId::UNSPECIFIED: ok = false; break; + } // clang-format on + } else { + ok = false; + } + NMEA_TRACE("GetSystemId(\"%s\")=%s system=%c", field.c_str(), ok ? "true" : "false", types::EnumToVal(system)); + return ok; +} + +// Get system Id +bool GetSignalId(NmeaSignalId& signalid, const std::string& field, const NmeaSystemId system) +{ + bool ok = true; + if (!field.empty()) { + switch (system) { // clang-format off + case NmeaSystemId::GPS_SBAS: switch ((NmeaSignalId)field[0]) { + case NmeaSignalId::GPS_L1CA: signalid = NmeaSignalId::GPS_L1CA; break; // = NmeaSignalId::SBAS_L1CA + case NmeaSignalId::GPS_L2CL: signalid = NmeaSignalId::GPS_L2CL; break; + case NmeaSignalId::GPS_L2CM: signalid = NmeaSignalId::GPS_L2CM; break; + case NmeaSignalId::GPS_L5I: signalid = NmeaSignalId::GPS_L5I; break; + case NmeaSignalId::GPS_L5Q: signalid = NmeaSignalId::GPS_L5Q; break; + default: ok = false; break; + } break; + case NmeaSystemId::GLO: switch ((NmeaSignalId)field[0]) { + case NmeaSignalId::GLO_L1OF: signalid = NmeaSignalId::GLO_L1OF; break; + case NmeaSignalId::GLO_L2OF: signalid = NmeaSignalId::GLO_L2OF; break; + default: ok = false; break; + } break; + case NmeaSystemId::GAL: switch ((NmeaSignalId)field[0]) { + case NmeaSignalId::GAL_E1: signalid = NmeaSignalId::GAL_E1; break; + case NmeaSignalId::GAL_E5A: signalid = NmeaSignalId::GAL_E5A; break; + case NmeaSignalId::GAL_E5B: signalid = NmeaSignalId::GAL_E5B; break; + default: ok = false; break; + } break; + case NmeaSystemId::BDS: switch ((NmeaSignalId)field[0]) { + case NmeaSignalId::BDS_B1ID: signalid = NmeaSignalId::BDS_B1ID; break; + case NmeaSignalId::BDS_B2ID: signalid = NmeaSignalId::BDS_B2ID; break; + case NmeaSignalId::BDS_B1C: signalid = NmeaSignalId::BDS_B1C; break; + case NmeaSignalId::BDS_B2A: signalid = NmeaSignalId::BDS_B2A; break; + default: ok = false; break; + } break; + case NmeaSystemId::QZSS: switch ((NmeaSignalId)field[0]) { + case NmeaSignalId::QZSS_L1CA: signalid = NmeaSignalId::QZSS_L1CA; break; + case NmeaSignalId::QZSS_L1S: signalid = NmeaSignalId::QZSS_L1S; break; + case NmeaSignalId::QZSS_L2CM: signalid = NmeaSignalId::QZSS_L2CM; break; + case NmeaSignalId::QZSS_L2CL: signalid = NmeaSignalId::QZSS_L2CL; break; + case NmeaSignalId::QZSS_L5I: signalid = NmeaSignalId::QZSS_L5I; break; + case NmeaSignalId::QZSS_L5Q: signalid = NmeaSignalId::QZSS_L5Q; break; + default: ok = false; break; + } break; + case NmeaSystemId::NAVIC: switch ((NmeaSignalId)field[0]) { + case NmeaSignalId::NAVIC_L5A: signalid = NmeaSignalId::NAVIC_L5A; break; + default: ok = false; break; + } break; + case NmeaSystemId::UNSPECIFIED: + ok = false; + break; + + } // clang-format on + } else { + ok = false; + } + NMEA_TRACE("GetSignalId(\"%s\")=%s signalid=%c", field.c_str(), ok ? "true" : "false", types::EnumToVal(signalid)); + return ok; +} + +// Convert talker ID to system ID +static NmeaSystemId TalkerIdToSystemId(const NmeaTalkerId talkerid) +{ + NmeaSystemId systemid = NmeaSystemId::UNSPECIFIED; + switch (talkerid) { // clang-format off + case NmeaTalkerId::GPS_SBAS: systemid = NmeaSystemId::GPS_SBAS; break; + case NmeaTalkerId::GLO: systemid = NmeaSystemId::GLO; break; + case NmeaTalkerId::GAL: systemid = NmeaSystemId::GAL; break; + case NmeaTalkerId::BDS: systemid = NmeaSystemId::BDS; break; + case NmeaTalkerId::NAVIC: systemid = NmeaSystemId::NAVIC; break; + case NmeaTalkerId::QZSS: systemid = NmeaSystemId::QZSS; break; + case NmeaTalkerId::GNSS: + case NmeaTalkerId::UNSPECIFIED: + case NmeaTalkerId::PROPRIETARY: break; + } // clang-format on + NMEA_TRACE("TalkerIdToSystemId(%c)=%c", types::EnumToVal(talkerid), types::EnumToVal(systemid)); + return systemid; +} + +static constexpr int INAN = std::numeric_limits::max(); + +// Get integer value +static bool GetInt( + NmeaInt& nmeaint, const std::string& field, const bool required, const int min = INAN, const int max = INAN) +{ + bool ok = true; + // Null field may be okay + if (field.empty()) { + if (required) { + ok = false; + } + } + // Otherwise we require a value + else { + int value = 0; + if (StrToInt(field, value)) { + // Range limits? + if ((min != INAN) && (value < min)) { + ok = false; + } + if ((max != INAN) && (value > max)) { + ok = false; + } + if (ok) { + nmeaint.value = value; + nmeaint.valid = true; + } + } else { + ok = false; + } + } + + NMEA_TRACE("GetInt(\"%s\", %s, %d, %d)=%s value=%d/%s", field.c_str(), required ? "true" : "false", min, max, + ok ? "true" : "false", nmeaint.value, nmeaint.valid ? "true" : "false"); + return ok; +} + +// Get float value +static bool GetFloat( + NmeaFloat& nmeafloat, const std::string& field, const bool required, const double min = NAN, const double max = NAN) +{ + bool ok = true; + // Null field may be okay + if (field.empty()) { + if (required) { + ok = false; + } + } + // Otherwise we require a value + else { + double value = 0.0; + if (StrToFloat(field, value)) { + // Range limits? + if (std::isfinite(min) && (value < min)) { + ok = false; + } + if (std::isfinite(max) && (value > max)) { + ok = false; + } + if (ok) { + nmeafloat.value = value; + nmeafloat.valid = true; + } + } else { + ok = false; + } + } + + NMEA_TRACE("GetFloat(\"%s\", %s, %g, %g)=%s value=%g/%s", field.c_str(), required ? "true" : "false", min, max, + ok ? "true" : "false", nmeafloat.value, nmeafloat.valid ? "true" : "false"); + return ok; +} + +// --------------------------------------------------------------------------------------------------------------------- + +bool NmeaGgaPayload::SetFromMsg(const uint8_t* msg, const std::size_t msg_size) +{ + // $GNGGA,092207.400,4724.017956,N,00827.022383,E,2,41,0.43,411.542,M,47.989,M,,*79\r\n + // 0 1 2 3 4 5 6 7 8 9 10 11 12 13 + // $GNGGA,235943.812,,,,,0,00,99.99,,M,,M,,*49 + // 14 or 12 fields as diff station info is optional + bool ok = false; + NmeaParts m; + if (GetParts(m, "GGA", msg, msg_size) && GetTalker(talker, m.meta_.talker_) && + ((m.fields_.size() == 14) || (m.fields_.size() == 12))) { + ok = (GetTime(time, m.fields_[0]) && GetQualityGga(quality, m.fields_[5]) && + GetLlh(llh, m.fields_, 1, 3, 8, 10, quality != NmeaQualityGga::NOFIX) && + GetInt(num_sv, m.fields_[6], false, 0, 200) && + ((quality == NmeaQualityGga::NOFIX) || GetFloat(hdop, m.fields_[7], true, 0.0)) && + ((m.fields_.size() == 12) || + (GetFloat(diff_age, m.fields_[12], false, 0, 1023) && GetInt(diff_sta, m.fields_[13], false, 0.0)))); + } + NMEA_TRACE("NmeaGgaPayload %s", ok ? "true" : "false"); + return ok; +} + +// --------------------------------------------------------------------------------------------------------------------- + +bool NmeaGllPayload::SetFromMsg(const uint8_t* msg, const std::size_t msg_size) +{ + // $GNGLL,4724.018931,N,00827.023090,E,110546.800,A,D*4F $GNGLL,,,,,235943.612,V,N*6B + // 0 1 2 3 4 5 6 + bool ok = false; + NmeaParts m; + if (GetParts(m, "GLL", msg, msg_size) && GetTalker(talker, m.meta_.talker_) && (m.fields_.size() == 7)) { + ok = (GetTime(time, m.fields_[4]) && GetStatusGllRmc(status, m.fields_[5]) && + GetModeGllVtg(mode, m.fields_[6]) && + GetLlh(llh, m.fields_, 0, 2, -1, -1, mode != NmeaModeGllVtg::INVALID)); + } + NMEA_TRACE("NmeaGllPayload %s", ok ? "true" : "false"); + return ok; +} + +// --------------------------------------------------------------------------------------------------------------------- + +bool NmeaRmcPayload::SetFromMsg(const uint8_t* msg, const std::size_t msg_size) +{ + // $GNRMC,110546.800,A,4724.018931,N,00827.023090,E,0.015,139.17,231024,,,D,V*3D + // 0 1 2 3 4 5 6 7 8 9 10 11 12 + // $GNRMC,235943.412,V,,,,,,,050180,,,N,V*28 + bool ok = false; + NmeaParts m; + if (GetParts(m, "RMC", msg, msg_size) && GetTalker(talker, m.meta_.talker_) && (m.fields_.size() == 13)) { + // Ignore magnetic variation fields_[9] and fields_[10] + ok = (GetTime(time, m.fields_[0]) && GetStatusGllRmc(status, m.fields_[1]) && + GetFloat(speed, m.fields_[6], false) && GetFloat(course, m.fields_[7], false, 0.0, 360.0) && + GetDateDdMmYy(date, m.fields_[8]) && GetModeRmcGns(mode, m.fields_[11]) && + GetNavStatusRmc(navstatus, m.fields_[12]) && + GetLlh(llh, m.fields_, 2, 4, -1, -1, mode != NmeaModeRmcGns::INVALID)); + } + NMEA_TRACE("NmeaRmcPayload %s", ok ? "true" : "false"); + return ok; +} + +// --------------------------------------------------------------------------------------------------------------------- + +bool NmeaVtgPayload::SetFromMsg(const uint8_t* msg, const std::size_t msg_size) +{ + // $GNVTG,139.17,T,,M,0.015,N,0.027,K,D*2A*4F $GNVTG,,T,,M,,N,,K,N*32 + // 0 1 23 4 5 6 7 8 + bool ok = false; + NmeaParts m; + if (GetParts(m, "VTG", msg, msg_size) && (m.fields_.size() == 9)) { + // Ignore magnetic course fields_[2] and fields_[3] + ok = (GetTalker(talker, m.meta_.talker_) && (m.fields_[1] == "T") && GetFloat(cogt, m.fields_[0], false) && + (m.fields_[5] == "N") && GetFloat(sogn, m.fields_[4], false) && (m.fields_[7] == "K") && + GetFloat(sogk, m.fields_[6], false) && GetModeGllVtg(mode, m.fields_[8])); + } + NMEA_TRACE("NmeaVtgPayload %s", ok ? "true" : "false"); + return ok; +} + +// --------------------------------------------------------------------------------------------------------------------- + +bool NmeaGsaPayload::SetFromMsg(const uint8_t* msg, const std::size_t msg_size) +{ + // $GNGSA,A,3,03,04,06,07,09,11,19,20,26,30,31,,0.79,0.46,0.64,1*0F + // 0 1 2 3 4 5 6 7 8 9 10 11 12 13 14 15 16 17 + // $GNGSA,A,1,,,,,,,,,,,,,99.99,99.99,99.99,5*37 + bool ok = false; + NmeaParts m; + if (GetParts(m, "GSA", msg, msg_size) && GetTalker(talker, m.meta_.talker_) && (m.fields_.size() == 18)) { + ok = GetSystemId(system, m.fields_[17]); + + // Satellites + for (std::size_t field_ix = 2; ok && (field_ix <= 13) && (field_ix < m.fields_.size()); field_ix++) { + if (!m.fields_[field_ix].empty()) { + NmeaSat cand; + if (GetSat(cand, m.fields_[field_ix], system, false) && cand.valid) { + sats[num_sats] = cand; + num_sats++; + } else { + ok = false; + } + } + } + + // Remaining fields + if (ok) { + ok = (GetOpModeGsa(opmode, m.fields_[0]) && GetNavModeGsa(navmode, m.fields_[1]) && + ((navmode == NmeaNavModeGsa::NOFIX) || GetFloat(pdop, m.fields_[14], true, 0.0)) && + ((navmode == NmeaNavModeGsa::NOFIX) || GetFloat(hdop, m.fields_[15], true, 0.0)) && + ((navmode == NmeaNavModeGsa::NOFIX) || GetFloat(vdop, m.fields_[16], true, 0.0))); + } + } + NMEA_TRACE("NmeaGsaPayload %s", ok ? "true" : "false"); + return ok; +} + +// --------------------------------------------------------------------------------------------------------------------- + +bool NmeaGsvPayload::SetFromMsg(const uint8_t* msg, const std::size_t msg_size) +{ + // Sequence of 4 messages, total 14 sats/sigs = 4 + 4 + 4 + 2 + // $GPGSV,4,2,14,09,84,270,52,11,28,311,46,16,03,080,42,17,03,218,35,1*69 + // 0 1 2 3 4 5 6 7 8 9 10 11 12 13 14 15 16 17 18 19 + // ^^^^^^^^^^^^ ^^^^^^^^^^^^ ^^^^^^^^^^^^ ^^^^^^^^^^^^ <-- 2nd message: 4 sigs/sats + // $GPGSV,4,4,14,31,08,034,46,36,31,149,43,1*62 + // 0 1 2 3 4 5 6 7 8 9 10 11 + // ^^^^^^^^^^^^ ^^^^^^^^^^^^ <-- 4th (last) message: 2 sigs/sats + // + // $GAGSV,1,1,00,1*75 + // 0 1 2 3 + bool ok = false; + NmeaParts m; + if (GetParts(m, "GSV", msg, msg_size) && GetTalker(talker, m.meta_.talker_)) { + // The number of fields depends on the number of satellites and the sequence of the message + static constexpr int MAX_MSGS = 9; + static constexpr int SV_PER_MSG = 4; + ok = ( + // - At least 4 fields are required + ((int)m.fields_.size() >= 4) && + // - The number of messages in the sequence + GetInt(num_msgs, m.fields_[0], true, 1, MAX_MSGS) && num_msgs.valid && + // - The message number in the sequence + GetInt(msg_num, m.fields_[1], true, 1, num_msgs.value) && msg_num.valid && + // - The total number of satellits in the sequence + GetInt(tot_num_sat, m.fields_[2], true, 0, MAX_MSGS * SV_PER_MSG) && tot_num_sat.valid); + // Determine the number of sat/sig in this message. The last message has the remainder, other messages have 4. + int num_sv = 0; + if (ok) { + const bool last_message = (msg_num.value == num_msgs.value); + num_sv = (last_message ? (tot_num_sat.value - ((msg_num.value - 1) * SV_PER_MSG)) : SV_PER_MSG); + ok = ((int)m.fields_.size() == (4 + (4 * num_sv))); + } + + // Now we know the field ix for the signal field. Note that GetSignalId() is only valid for certain talkers. So + // the checks below should give us an ok for valid talker/system and signal, and false otherwise. + system = TalkerIdToSystemId(talker); + signal = NmeaSignalId::UNSPECIFIED; + if (ok) { + ok = (GetSignalId(signal, m.fields_[3 + (num_sv * 4)], system) && (system != NmeaSystemId::UNSPECIFIED) && + (signal != NmeaSignalId::UNSPECIFIED)); + } + + // Read the sat/sig and populate the AzEl and Cno arrays + for (std::size_t field_offs = 3; + ok && ((int)field_offs < (3 + (num_sv * 4))) && ((field_offs + 3) < m.fields_.size()); field_offs += 4) { + NmeaSat sat; + NmeaInt el; + NmeaInt az; + NmeaInt cno; + if (GetSat(sat, m.fields_[field_offs], system, true) && sat.valid && + GetInt(el, m.fields_[field_offs + 1], false, -90, 90) && + GetInt(az, m.fields_[field_offs + 2], false, 0, 360) && + GetInt(cno, m.fields_[field_offs + 3], false, 0, 100)) { + // Have az/el + if (el.valid && az.valid) { + azels[num_azels].valid = true; + azels[num_azels].system = system; + azels[num_azels].svid = sat.svid; + azels[num_azels].az = az.value; + azels[num_azels].el = el.value; + num_azels++; + } + // Have cno + if (cno.valid) { + cnos[num_cnos].valid = true; + cnos[num_cnos].system = system; + cnos[num_cnos].svid = sat.svid; + cnos[num_cnos].signal = signal; + cnos[num_cnos].cno = cno.value; + num_cnos++; + } + } else { + ok = false; + } + } + } + NMEA_TRACE("NmeaGsvPayload %s", ok ? "true" : "false"); + return ok; +} + +// --------------------------------------------------------------------------------------------------------------------- + +bool NmeaCollectGsaGsv::AddGsaAndGsv(const std::vector& gsas, const std::vector& gsvs) +{ + bool ok = true; + for (auto& gsa : gsas) { + if (!AddGsa(gsa)) { + ok = false; + } + } + for (auto& gsv : gsvs) { + if (!AddGsv(gsv)) { + ok = false; + } + } + NMEA_TRACE("AddGsaAndGsv(%d, %d)=%s", (int)gsas.size(), (int)gsvs.size(), ok ? "true" : "false"); + if (ok) { + Complete(); + } + return ok; +} + +bool NmeaCollectGsaGsv::AddGsa(const NmeaGsaPayload& gsa) +{ + // Collect all "satellites used" from GSA message. They have no numbering, so we have to rely on the user giving us + // all messages. + for (auto& gsa_sat : gsa.sats) { + if (gsa_sat.valid) { + NMEA_TRACE("AddGsa() sat %c %d", types::EnumToVal(gsa_sat.system), gsa_sat.svid); + gsa_sats_.push_back(gsa_sat); + } + } + + NMEA_TRACE("AddGsa(%d, %c) gsa_sats_=%d", gsa.num_sats, types::EnumToVal(gsa.system), (int)gsa_sats_.size()); + + // @todo: Add checks on expected sequence of messages maybe? How? Maybe check that a message for each GNSS was seen? + // Check for duplicate SVs, ... + + return true; +} + +bool NmeaCollectGsaGsv::AddGsv(const NmeaGsvPayload& gsv) +{ + // @todo: Add checks on expected sequence of messages maybe? We could use the msg_num and num_msgs fields and check + // that a set of messages for each GNSS was seen. Check for duplicate SVs, ... + + // Satellite info. + for (auto& gsv_azel : gsv.azels) { + // Also check that we don't have this SV already *sat* info is reported repeatedly in the GSV message*s* if + // there are multiple signals tracked for the satellite. + auto entry = std::find_if(sats_.cbegin(), sats_.cend(), [&gsv_azel](const auto& cand) { + return (cand.system_ == gsv_azel.system) && (cand.svid_ == gsv_azel.svid); + }); + if (gsv_azel.valid && (entry == sats_.cend())) { + Sat sat; + sat.system_ = gsv_azel.system; + sat.svid_ = gsv_azel.svid; + sat.az_ = gsv_azel.az; + sat.el_ = gsv_azel.el; + NMEA_TRACE("AddGsv() sat %c %d %d %d", types::EnumToVal(sat.system_), sat.svid_, sat.az_, sat.el_); + sats_.push_back(sat); + } + } + + // Signal info + for (auto& gsv_cno : gsv.cnos) { + if (gsv_cno.valid) { + Sig sig; + sig.system_ = gsv_cno.system; + sig.svid_ = gsv_cno.svid; + sig.signal_ = gsv_cno.signal; + sig.cno_ = gsv_cno.cno; + // If satellite is listed as used in GSA, assume the signal is used. Even though it may be wrong (e.g. for a + // sat only L1 is used and L2 is only tracked) this is the best we can do with the NMEA data. + const auto entry = std::find_if(gsa_sats_.cbegin(), gsa_sats_.cend(), + [&sig](const auto& cand) { return (cand.system == sig.system_) && (cand.svid == sig.svid_); }); + sig.used_ = (entry != gsa_sats_.cend()); + NMEA_TRACE("AddGsv() sig %c %c %d %.1f %s", types::EnumToVal(sig.system_), types::EnumToVal(sig.signal_), + sig.svid_, sig.cno_, sig.used_ ? "used" : "-"); + sigs_.push_back(sig); + } + } + + NMEA_TRACE("AddGsv(%d/%s, %d/%s, %c, %c, %d, %d) sats_=%d sigs_=%d", gsv.msg_num.value, + gsv.msg_num.valid ? "true" : "false", gsv.num_msgs.value, gsv.num_msgs.valid ? "true" : "false", + types::EnumToVal(gsv.system), types::EnumToVal(gsv.signal), gsv.num_azels, gsv.num_cnos, (int)sats_.size(), + (int)sigs_.size()); + + return true; +} + +void NmeaCollectGsaGsv::Complete() +{ + // No longer needed + gsa_sats_.clear(); + + // Order by system and svid + std::sort(sats_.begin(), sats_.end(), [](const auto& a, const auto& b) { + return (a.system_ == b.system_) ? (a.svid_ < b.svid_) : (a.system_ < b.system_); + }); + // Order by system, signal and svid + std::sort(sigs_.begin(), sigs_.end(), [](const auto& a, const auto& b) { + return (a.system_ == b.system_) ? ((a.signal_ == b.signal_) ? (a.svid_ < b.svid_) : (a.signal_ < b.signal_)) + : (a.system_ < b.system_); + }); + + for (std::size_t ix = 0; ix < sats_.size(); ix++) { + NMEA_TRACE("NmeaCollectGsaGsv() sats_[%d] %c %d %d %d", (int)ix, types::EnumToVal(sats_[ix].system_), + sats_[ix].svid_, sats_[ix].az_, sats_[ix].el_); + } + for (std::size_t ix = 0; ix < sigs_.size(); ix++) { + NMEA_TRACE("NmeaCollectGsaGsv() sigs_[%d] %c %c %d %.1f %s", (int)ix, types::EnumToVal(sigs_[ix].system_), + types::EnumToVal(sigs_[ix].signal_), sigs_[ix].svid_, sigs_[ix].cno_, sigs_[ix].used_ ? "used" : "-"); + } +} + +/* ****************************************************************************************************************** */ +} // namespace nmea +} // namespace parser +} // namespace common +} // namespace fpsdk diff --git a/fpsdk_common/src/parser/novb.cpp b/fpsdk_common/src/parser/novb.cpp new file mode 100644 index 0000000..6a1e858 --- /dev/null +++ b/fpsdk_common/src/parser/novb.cpp @@ -0,0 +1,189 @@ +/** + * \verbatim + * ___ ___ + * \ \ / / + * \ \/ / Copyright (c) Fixposition AG (www.fixposition.com) and contributors + * / /\ \ License: see the LICENSE file + * /__/ \__\ + * + * Parts copyright (c) 2020 NovAtel Inc. + * Based on work by flipflip (https://github.com/phkehl) + * \endverbatim + * + * @file + * @brief Fixposition SDK: Parser NOV_B routines and types + */ + +/* LIBC/STL */ +#include +#include +#include +#include +#include +#include + +/* EXTERNAL */ + +/* PACKAGE */ +#include "fpsdk_common/parser/novb.hpp" + +namespace fpsdk { +namespace common { +namespace parser { +namespace novb { +/* ****************************************************************************************************************** */ + +// Lookup table entry +struct MsgInfo +{ + uint16_t msg_id; + const char* name; +}; + +// clang-format off +// @fp_codegen_begin{FPSDK_COMMON_PARSER_NOVB_MSGINFO} +static constexpr std::array MSG_INFO = +{{ + { NOV_B_BESTGNSSPOS_MSGID, NOV_B_BESTGNSSPOS_STRID }, + { NOV_B_BESTPOS_MSGID, NOV_B_BESTPOS_STRID }, + { NOV_B_BESTUTM_MSGID, NOV_B_BESTUTM_STRID }, + { NOV_B_BESTVEL_MSGID, NOV_B_BESTVEL_STRID }, + { NOV_B_BESTXYZ_MSGID, NOV_B_BESTXYZ_STRID }, + { NOV_B_CORRIMUS_MSGID, NOV_B_CORRIMUS_STRID }, + { NOV_B_HEADING2_MSGID, NOV_B_HEADING2_STRID }, + { NOV_B_IMURATECORRIMUS_MSGID, NOV_B_IMURATECORRIMUS_STRID }, + { NOV_B_INSCONFIG_MSGID, NOV_B_INSCONFIG_STRID }, + { NOV_B_INSPVA_MSGID, NOV_B_INSPVA_STRID }, + { NOV_B_INSPVAS_MSGID, NOV_B_INSPVAS_STRID }, + { NOV_B_INSPVAX_MSGID, NOV_B_INSPVAX_STRID }, + { NOV_B_INSSTDEV_MSGID, NOV_B_INSSTDEV_STRID }, + { NOV_B_PSRDOP2_MSGID, NOV_B_PSRDOP2_STRID }, + { NOV_B_RAWDMI_MSGID, NOV_B_RAWDMI_STRID }, + { NOV_B_RAWIMU_MSGID, NOV_B_RAWIMU_STRID }, + { NOV_B_RAWIMUSX_MSGID, NOV_B_RAWIMUSX_STRID }, + { NOV_B_RXSTATUS_MSGID, NOV_B_RXSTATUS_STRID }, + { NOV_B_TIME_MSGID, NOV_B_TIME_STRID }, +}}; +// @fp_codegen_end{FPSDK_COMMON_PARSER_NOVB_MSGINFO} +// clang-format on + +bool NovbGetMessageName(char* name, const std::size_t size, const uint8_t* msg, const std::size_t msg_size) +{ + // Check arguments + if ((name == NULL) || (size < 1)) { + return false; + } + name[0] = '\0'; + + if ((msg == NULL) || (msg_size < 14)) { + return false; + } + + const uint16_t msg_id = NovbMsgId(msg); + + // Try the message name lookup table + for (auto& info : MSG_INFO) { + if (info.msg_id == msg_id) { + return std::snprintf(name, size, "%s", info.name) < (int)size; + } + } + + // If that failed, too, stringify the message ID + return std::snprintf(name, size, "NOV_B-MSG%05" PRIu16, msg_id) < (int)size; +} + +// --------------------------------------------------------------------------------------------------------------------- + +const char* NovbMsgTypeSourceStr(const uint8_t message_type) +{ + // clang-format off + switch (static_cast(message_type & static_cast(NovbMsgTypeSource::_MASK))) { + case NovbMsgTypeSource::PRIMARY: return "PRIMARY"; + case NovbMsgTypeSource::SECONDARY: return "SECONDARY"; + case NovbMsgTypeSource::_MASK: break; + } // clang-format on + return "?"; +} + +// --------------------------------------------------------------------------------------------------------------------- + +const char* NovbTimeStatusStr(const NovbTimeStatus time_status) +{ + switch (time_status) { // clang-format off + case NovbTimeStatus::UNKNOWN: return "UNKNOWN"; + case NovbTimeStatus::APPROXIMATE: return "APPROXIMATE"; + case NovbTimeStatus::COARSEADJUSTING: return "COARSEADJUSTING"; + case NovbTimeStatus::COARSE: return "COARSE"; + case NovbTimeStatus::COARSESTEERING: return "COARSESTEERING"; + case NovbTimeStatus::FREEWHEELING: return "FREEWHEELING"; + case NovbTimeStatus::FINEADJUSTING: return "FINEADJUSTING"; + case NovbTimeStatus::FINE: return "FINE"; + case NovbTimeStatus::FINEBACKUPSTEERING: return "FINEBACKUPSTEERING"; + case NovbTimeStatus::FINESTEERING: return "FINESTEERING"; + case NovbTimeStatus::SATTIME: return "SATTIME"; + } // clang-format on + return "?"; +} + +// --------------------------------------------------------------------------------------------------------------------- + +#define _CHKSIZE(_type_) \ + (((msg[2] == NOV_B_SYNC_3_LONG) && (msg_size == (NOV_B_HEAD_SIZE_SHORT + sizeof(_type_) + 4))) || \ + ((msg[2] == NOV_B_SYNC_3_SHORT) && (msg_size == (NOV_B_HEAD_SIZE_LONG + sizeof(_type_) + 4)))) + +#define _PAYLOAD(_type_, _dst_) \ + _type_ _dst_; \ + memcpy(&_dst_, &msg[msg[2] == NOV_B_SYNC_3_LONG ? NOV_B_HEAD_SIZE_LONG : NOV_B_HEAD_SIZE_SHORT], sizeof(_dst_)) + +static std::size_t StrNovbRawdmi(char* info, const std::size_t size, const uint8_t* msg, const std::size_t msg_size) +{ + std::size_t len = 0; + if (_CHKSIZE(NovbRawdmi)) { + _PAYLOAD(NovbRawdmi, dmi); + len += snprintf(&info[len], size - len, " [%c]=%d [%c]=%d [%c]=%d [%c]=%d", dmi.dmi1_valid ? '1' : '.', + dmi.dmi1, dmi.dmi2_valid ? '2' : '.', dmi.dmi2, dmi.dmi3_valid ? '3' : '.', dmi.dmi3, + dmi.dmi4_valid ? '4' : '.', dmi.dmi4); + } + return len; +} + +// --------------------------------------------------------------------------------------------------------------------- + +bool NovbGetMessageInfo(char* info, const std::size_t size, const uint8_t* msg, const std::size_t msg_size) +{ + if ((info == NULL) || (size < 1)) { + return false; + } + + if ((msg == NULL) || (msg_size < NOV_B_HEAD_SIZE_SHORT)) { + info[0] = '\0'; + return false; + } + std::size_t len = 0; + + // Common stringification + if (NovbIsLongHeader(msg) && (msg_size >= NOV_B_HEAD_SIZE_LONG)) { + NovbLongHeader hdr; + std::memcpy(&hdr, msg, sizeof(hdr)); + len += snprintf(&info[len], size - len, "l %010.3f", (double)hdr.gps_milliseconds * 1e-3); + } else if (NovbIsShortHeader(msg) && (msg_size >= NOV_B_HEAD_SIZE_SHORT)) { + NovbShortHeader hdr; + std::memcpy(&hdr, msg, sizeof(hdr)); + len += snprintf(&info[len], size - len, "s %010.3f", (double)hdr.gps_milliseconds * 1e-3); + } + + // Specific stringification for some messages + switch (NovbMsgId(msg)) { + case NOV_B_RAWDMI_MSGID: + len += StrNovbRawdmi(&info[len], size - len, msg, msg_size); + break; + } + + return (len > 0) && (len < size); +} + +/* ****************************************************************************************************************** */ +} // namespace novb +} // namespace parser +} // namespace common +} // namespace fpsdk diff --git a/fpsdk_common/src/parser/rtcm3.cpp b/fpsdk_common/src/parser/rtcm3.cpp new file mode 100644 index 0000000..e241d5d --- /dev/null +++ b/fpsdk_common/src/parser/rtcm3.cpp @@ -0,0 +1,472 @@ +/** + * \verbatim + * ___ ___ + * \ \ / / + * \ \/ / Copyright (c) Fixposition AG (www.fixposition.com) and contributors + * / /\ \ License: see the LICENSE file + * /__/ \__\ + * + * Based on work by flipflip (https://github.com/phkehl) + * \endverbatim + * + * @file + * @brief Fixposition SDK: Parser RTCM3 routines and types + */ + +/* LIBC/STL */ +#include +#include +#include +#include + +/* EXTERNAL */ + +/* PACKAGE */ +#include "fpsdk_common/parser/rtcm3.hpp" +#include "fpsdk_common/types.hpp" + +namespace fpsdk { +namespace common { +namespace parser { +namespace rtcm3 { +/* ****************************************************************************************************************** */ + +// Lookup table entry +struct MsgInfo +{ + uint16_t type_; + uint16_t subtype_; + const char* name_; + const char* desc_; +}; + +// clang-format off +// @fp_codegen_begin{FPSDK_COMMON_PARSER_RTCM3_MSGINFO} +static constexpr std::array MSG_INFO = +{{ + { RTCM3_TYPE1001_MSGID, 0, RTCM3_TYPE1001_STRID, "L1-only GPS RTK observables" }, + { RTCM3_TYPE1002_MSGID, 0, RTCM3_TYPE1002_STRID, "Extended L1-only GPS RTK observables" }, + { RTCM3_TYPE1003_MSGID, 0, RTCM3_TYPE1003_STRID, "L1/L2 GPS RTK observables" }, + { RTCM3_TYPE1004_MSGID, 0, RTCM3_TYPE1004_STRID, "Extended L1/L2 GPS RTK observables" }, + { RTCM3_TYPE1005_MSGID, 0, RTCM3_TYPE1005_STRID, "Stationary RTK reference station ARP" }, + { RTCM3_TYPE1006_MSGID, 0, RTCM3_TYPE1006_STRID, "Stationary RTK reference station ARP with antenna height" }, + { RTCM3_TYPE1007_MSGID, 0, RTCM3_TYPE1007_STRID, "Antenna descriptor" }, + { RTCM3_TYPE1008_MSGID, 0, RTCM3_TYPE1008_STRID, "Antenna descriptor and serial number" }, + { RTCM3_TYPE1009_MSGID, 0, RTCM3_TYPE1009_STRID, "L1-only GLONASS RTK observables" }, + { RTCM3_TYPE1010_MSGID, 0, RTCM3_TYPE1010_STRID, "Extended L1-only GLONASS RTK observables" }, + { RTCM3_TYPE1011_MSGID, 0, RTCM3_TYPE1011_STRID, "L1/L2 GLONASS RTK observables" }, + { RTCM3_TYPE1012_MSGID, 0, RTCM3_TYPE1012_STRID, "Extended L1/L2 GLONASS RTK observables" }, + { RTCM3_TYPE1030_MSGID, 0, RTCM3_TYPE1030_STRID, "GPS network RTK residual message" }, + { RTCM3_TYPE1031_MSGID, 0, RTCM3_TYPE1031_STRID, "GLONASS network RTK residual message" }, + { RTCM3_TYPE1032_MSGID, 0, RTCM3_TYPE1032_STRID, "Physical reference station position message" }, + { RTCM3_TYPE1033_MSGID, 0, RTCM3_TYPE1033_STRID, "Receiver and antenna descriptors" }, + { RTCM3_TYPE1230_MSGID, 0, RTCM3_TYPE1230_STRID, "GLONASS code-phase biases" }, + { RTCM3_TYPE1071_MSGID, 0, RTCM3_TYPE1071_STRID, "GPS MSM1 (C)" }, + { RTCM3_TYPE1072_MSGID, 0, RTCM3_TYPE1072_STRID, "GPS MSM2 (L)" }, + { RTCM3_TYPE1073_MSGID, 0, RTCM3_TYPE1073_STRID, "GPS MSM3 (C, L)" }, + { RTCM3_TYPE1074_MSGID, 0, RTCM3_TYPE1074_STRID, "GPS MSM4 (full C, full L, S)" }, + { RTCM3_TYPE1075_MSGID, 0, RTCM3_TYPE1075_STRID, "GPS MSM5 (full C, full L, S, D)" }, + { RTCM3_TYPE1076_MSGID, 0, RTCM3_TYPE1076_STRID, "GPS MSM6 (ext full C, ext full L, S)" }, + { RTCM3_TYPE1077_MSGID, 0, RTCM3_TYPE1077_STRID, "GPS MSM7 (ext full C, ext full L, S, D)" }, + { RTCM3_TYPE1081_MSGID, 0, RTCM3_TYPE1081_STRID, "GLONASS MSM1 (C)" }, + { RTCM3_TYPE1082_MSGID, 0, RTCM3_TYPE1082_STRID, "GLONASS MSM2 (L)" }, + { RTCM3_TYPE1083_MSGID, 0, RTCM3_TYPE1083_STRID, "GLONASS MSM3 (C, L)" }, + { RTCM3_TYPE1084_MSGID, 0, RTCM3_TYPE1084_STRID, "GLONASS MSM4 (full C, full L, S)" }, + { RTCM3_TYPE1085_MSGID, 0, RTCM3_TYPE1085_STRID, "GLONASS MSM5 (full C, full L, S, D)" }, + { RTCM3_TYPE1086_MSGID, 0, RTCM3_TYPE1086_STRID, "GLONASS MSM6 (ext full C, ext full L, S)" }, + { RTCM3_TYPE1087_MSGID, 0, RTCM3_TYPE1087_STRID, "GLONASS MSM7 (ext full C, ext full L, S, D)" }, + { RTCM3_TYPE1091_MSGID, 0, RTCM3_TYPE1091_STRID, "Galileo MSM1 (C)" }, + { RTCM3_TYPE1092_MSGID, 0, RTCM3_TYPE1092_STRID, "Galileo MSM2 (L)" }, + { RTCM3_TYPE1093_MSGID, 0, RTCM3_TYPE1093_STRID, "Galileo MSM3 (C, L)" }, + { RTCM3_TYPE1094_MSGID, 0, RTCM3_TYPE1094_STRID, "Galileo MSM4 (full C, full L, S)" }, + { RTCM3_TYPE1095_MSGID, 0, RTCM3_TYPE1095_STRID, "Galileo MSM5 (full C, full L, S, D)" }, + { RTCM3_TYPE1096_MSGID, 0, RTCM3_TYPE1096_STRID, "Galileo MSM6 (full C, full L, S)" }, + { RTCM3_TYPE1097_MSGID, 0, RTCM3_TYPE1097_STRID, "Galileo MSM7 (ext full C, ext full L, S, D)" }, + { RTCM3_TYPE1101_MSGID, 0, RTCM3_TYPE1101_STRID, "SBAS MSM1 (C)" }, + { RTCM3_TYPE1102_MSGID, 0, RTCM3_TYPE1102_STRID, "SBAS MSM2 (L)" }, + { RTCM3_TYPE1103_MSGID, 0, RTCM3_TYPE1103_STRID, "SBAS MSM3 (C, L)" }, + { RTCM3_TYPE1104_MSGID, 0, RTCM3_TYPE1104_STRID, "SBAS MSM4 (full C, full L, S)" }, + { RTCM3_TYPE1105_MSGID, 0, RTCM3_TYPE1105_STRID, "SBAS MSM5 (full C, full L, S, D)" }, + { RTCM3_TYPE1106_MSGID, 0, RTCM3_TYPE1106_STRID, "SBAS MSM6 (full C, full L, S)" }, + { RTCM3_TYPE1107_MSGID, 0, RTCM3_TYPE1107_STRID, "SBAS MSM7 (ext full C, ext full L, S, D)" }, + { RTCM3_TYPE1111_MSGID, 0, RTCM3_TYPE1111_STRID, "QZSS MSM1 (C)" }, + { RTCM3_TYPE1112_MSGID, 0, RTCM3_TYPE1112_STRID, "QZSS MSM2 (L)" }, + { RTCM3_TYPE1113_MSGID, 0, RTCM3_TYPE1113_STRID, "QZSS MSM3 (C, L)" }, + { RTCM3_TYPE1114_MSGID, 0, RTCM3_TYPE1114_STRID, "QZSS MSM4 (full C, full L, S)" }, + { RTCM3_TYPE1115_MSGID, 0, RTCM3_TYPE1115_STRID, "QZSS MSM5 (full C, full L, S, D)" }, + { RTCM3_TYPE1116_MSGID, 0, RTCM3_TYPE1116_STRID, "QZSS MSM6 (full C, full L, S)" }, + { RTCM3_TYPE1117_MSGID, 0, RTCM3_TYPE1117_STRID, "QZSS MSM7 (ext full C, ext full L, S, D)" }, + { RTCM3_TYPE1121_MSGID, 0, RTCM3_TYPE1121_STRID, "BeiDou MSM1 (C)" }, + { RTCM3_TYPE1122_MSGID, 0, RTCM3_TYPE1122_STRID, "BeiDou MSM2 (L)" }, + { RTCM3_TYPE1123_MSGID, 0, RTCM3_TYPE1123_STRID, "BeiDou MSM3 (C, L)" }, + { RTCM3_TYPE1124_MSGID, 0, RTCM3_TYPE1124_STRID, "BeiDou MSM4 (full C, full L, S)" }, + { RTCM3_TYPE1125_MSGID, 0, RTCM3_TYPE1125_STRID, "BeiDou MSM5 (full C, full L, S, D)" }, + { RTCM3_TYPE1126_MSGID, 0, RTCM3_TYPE1126_STRID, "BeiDou MSM6 (full C, full L, S)" }, + { RTCM3_TYPE1127_MSGID, 0, RTCM3_TYPE1127_STRID, "BeiDou MSM7 (ext full C, ext full L, S, D)" }, + { RTCM3_TYPE1131_MSGID, 0, RTCM3_TYPE1131_STRID, "NavIC MSM1 (C)" }, + { RTCM3_TYPE1132_MSGID, 0, RTCM3_TYPE1132_STRID, "NavIC MSM2 (L)" }, + { RTCM3_TYPE1133_MSGID, 0, RTCM3_TYPE1133_STRID, "NavIC MSM3 (C, L)" }, + { RTCM3_TYPE1134_MSGID, 0, RTCM3_TYPE1134_STRID, "NavIC MSM4 (full C, full L, S)" }, + { RTCM3_TYPE1135_MSGID, 0, RTCM3_TYPE1135_STRID, "NavIC MSM5 (full C, full L, S, D)" }, + { RTCM3_TYPE1136_MSGID, 0, RTCM3_TYPE1136_STRID, "NavIC MSM6 (full C, full L, S)" }, + { RTCM3_TYPE1137_MSGID, 0, RTCM3_TYPE1137_STRID, "NavIC MSM7 (ext full C, ext full L, S, D)" }, + { RTCM3_TYPE1019_MSGID, 0, RTCM3_TYPE1019_STRID, "GPS ephemerides" }, + { RTCM3_TYPE1020_MSGID, 0, RTCM3_TYPE1020_STRID, "GLONASS ephemerides" }, + { RTCM3_TYPE1042_MSGID, 0, RTCM3_TYPE1042_STRID, "BeiDou satellite ephemeris data" }, + { RTCM3_TYPE1044_MSGID, 0, RTCM3_TYPE1044_STRID, "QZSS ephemerides" }, + { RTCM3_TYPE1045_MSGID, 0, RTCM3_TYPE1045_STRID, "Galileo F/NAV satellite ephemeris data" }, + { RTCM3_TYPE1046_MSGID, 0, RTCM3_TYPE1046_STRID, "Galileo I/NAV satellite ephemeris data" }, + { RTCM3_TYPE4050_MSGID, 0, RTCM3_TYPE4050_STRID, "STMicroelectronics proprietary" }, + { RTCM3_TYPE4051_MSGID, 0, RTCM3_TYPE4051_STRID, "Hi-Target proprietary" }, + { RTCM3_TYPE4052_MSGID, 0, RTCM3_TYPE4052_STRID, "Furuno proprietary" }, + { RTCM3_TYPE4053_MSGID, 0, RTCM3_TYPE4053_STRID, "Qualcomm proprietary" }, + { RTCM3_TYPE4054_MSGID, 0, RTCM3_TYPE4054_STRID, "Geodnet proprietary" }, + { RTCM3_TYPE4055_MSGID, 0, RTCM3_TYPE4055_STRID, "KRISO proprietary" }, + { RTCM3_TYPE4056_MSGID, 0, RTCM3_TYPE4056_STRID, "Dayou proprietary" }, + { RTCM3_TYPE4057_MSGID, 0, RTCM3_TYPE4057_STRID, "Sixents proprietary" }, + { RTCM3_TYPE4058_MSGID, 0, RTCM3_TYPE4058_STRID, "Anello proprietary" }, + { RTCM3_TYPE4059_MSGID, 0, RTCM3_TYPE4059_STRID, "NRCan proprietary" }, + { RTCM3_TYPE4060_MSGID, 0, RTCM3_TYPE4060_STRID, "ALES proprietary" }, + { RTCM3_TYPE4061_MSGID, 0, RTCM3_TYPE4061_STRID, "Geely proprietary" }, + { RTCM3_TYPE4062_MSGID, 0, RTCM3_TYPE4062_STRID, "SwiftNav proprietary" }, + { RTCM3_TYPE4063_MSGID, 0, RTCM3_TYPE4063_STRID, "CHCNAV proprietary" }, + { RTCM3_TYPE4064_MSGID, 0, RTCM3_TYPE4064_STRID, "NTLab proprietary" }, + { RTCM3_TYPE4065_MSGID, 0, RTCM3_TYPE4065_STRID, "Allystar proprietary" }, + { RTCM3_TYPE4066_MSGID, 0, RTCM3_TYPE4066_STRID, "Lantmateriet proprietary" }, + { RTCM3_TYPE4067_MSGID, 0, RTCM3_TYPE4067_STRID, "CIPPE proprietary" }, + { RTCM3_TYPE4068_MSGID, 0, RTCM3_TYPE4068_STRID, "Qianxun proprietary" }, + { RTCM3_TYPE4069_MSGID, 0, RTCM3_TYPE4069_STRID, "Veripos proprietary" }, + { RTCM3_TYPE4070_MSGID, 0, RTCM3_TYPE4070_STRID, "Wuhan MengXin proprietary" }, + { RTCM3_TYPE4071_MSGID, 0, RTCM3_TYPE4071_STRID, "Wuhan Navigation proprietary" }, + { RTCM3_TYPE4072_MSGID, 0, RTCM3_TYPE4072_STRID, "u-blox proprietary" }, + { RTCM3_TYPE4073_MSGID, 0, RTCM3_TYPE4073_STRID, "Mitsubishi proprietary" }, + { RTCM3_TYPE4074_MSGID, 0, RTCM3_TYPE4074_STRID, "Unicore proprietary" }, + { RTCM3_TYPE4075_MSGID, 0, RTCM3_TYPE4075_STRID, "Alberding proprietary" }, + { RTCM3_TYPE4076_MSGID, 0, RTCM3_TYPE4076_STRID, "IGS proprietary" }, + { RTCM3_TYPE4077_MSGID, 0, RTCM3_TYPE4077_STRID, "Hemisphere proprietary" }, + { RTCM3_TYPE4078_MSGID, 0, RTCM3_TYPE4078_STRID, "ComNav proprietary" }, + { RTCM3_TYPE4079_MSGID, 0, RTCM3_TYPE4079_STRID, "SubCarrier proprietary" }, + { RTCM3_TYPE4080_MSGID, 0, RTCM3_TYPE4080_STRID, "NavCom proprietary" }, + { RTCM3_TYPE4081_MSGID, 0, RTCM3_TYPE4081_STRID, "SNU GNSS proprietary" }, + { RTCM3_TYPE4082_MSGID, 0, RTCM3_TYPE4082_STRID, "CRCSI proprietary" }, + { RTCM3_TYPE4083_MSGID, 0, RTCM3_TYPE4083_STRID, "DLR proprietary" }, + { RTCM3_TYPE4084_MSGID, 0, RTCM3_TYPE4084_STRID, "Geodetics, Inc proprietary" }, + { RTCM3_TYPE4085_MSGID, 0, RTCM3_TYPE4085_STRID, "EUSPA proprietary" }, + { RTCM3_TYPE4086_MSGID, 0, RTCM3_TYPE4086_STRID, "inPosition proprietary" }, + { RTCM3_TYPE4087_MSGID, 0, RTCM3_TYPE4087_STRID, "Fugro proprietary" }, + { RTCM3_TYPE4088_MSGID, 0, RTCM3_TYPE4088_STRID, "IfEN proprietary" }, + { RTCM3_TYPE4089_MSGID, 0, RTCM3_TYPE4089_STRID, "Septentrio proprietary" }, + { RTCM3_TYPE4090_MSGID, 0, RTCM3_TYPE4090_STRID, "Geo++ proprietary" }, + { RTCM3_TYPE4091_MSGID, 0, RTCM3_TYPE4091_STRID, "Topcon proprietary" }, + { RTCM3_TYPE4092_MSGID, 0, RTCM3_TYPE4092_STRID, "Leica proprietary" }, + { RTCM3_TYPE4093_MSGID, 0, RTCM3_TYPE4093_STRID, "NovAtel proprietary" }, + { RTCM3_TYPE4094_MSGID, 0, RTCM3_TYPE4094_STRID, "Trimble proprietary" }, + { RTCM3_TYPE4095_MSGID, 0, RTCM3_TYPE4095_STRID, "Ashtech proprietary" }, +}}; +static constexpr std::array SUB_INFO = +{{ + { RTCM3_TYPE4072_MSGID, RTCM3_TYPE4072_0_SUBID, RTCM3_TYPE4072_0_STRID, "u-blox proprietary: Reference station PVT" }, + { RTCM3_TYPE4072_MSGID, RTCM3_TYPE4072_1_SUBID, RTCM3_TYPE4072_1_STRID, "u-blox proprietary: Additional reference station information" }, +}}; +// @fp_codegen_end{FPSDK_COMMON_PARSER_RTCM3_MSGINFO} +// clang-format on + +// --------------------------------------------------------------------------------------------------------------------- + +bool Rtcm3GetMessageName(char* name, const std::size_t size, const uint8_t* msg, const std::size_t msg_size) +{ + // Check arguments + if ((name == NULL) || (size < 1)) { + return false; + } + name[0] = '\0'; + + if ((msg == NULL) || (msg_size < (RTCM3_FRAME_SIZE + 3))) { + return false; + } + + const uint16_t type = Rtcm3Type(msg); + + // Try sub-type lookup table for proprietary messages + if ((type >= 4001) && (type <= 4095)) { + const uint16_t subtype = Rtcm3SubType(msg); // maybe.. + for (auto& info : SUB_INFO) { + if ((info.type_ == type) && (info.subtype_ == subtype)) { + return std::snprintf(name, size, "%s", info.name_) < (int)size; + } + } + } + + // Try the message name lookup table + for (auto& info : MSG_INFO) { + if (info.type_ == type) { + return std::snprintf(name, size, "%s", info.name_) < (int)size; + } + } + + return std::snprintf(name, size, "RTCM3-TYPE%" PRIu16, type) < (int)size; +} + +// --------------------------------------------------------------------------------------------------------------------- + +const char* Rtcm3GetTypeDesc(const uint16_t type, const uint16_t subtype) +{ + if ((type >= 4001) && (type <= 4095)) { + for (auto& info : SUB_INFO) { + if ((info.type_ == type) && (info.subtype_ == subtype)) { + return info.desc_; + } + } + } + for (auto& info : MSG_INFO) { + if (info.type_ == type) { + return info.desc_; + } + } + return NULL; +} + +// --------------------------------------------------------------------------------------------------------------------- + +uint64_t Rtcm3GetUnsigned(const uint8_t* data, const std::size_t offs, const std::size_t size) +{ + uint64_t val = 0; + if ((data != NULL) && (size > 0)) { + for (std::size_t bo = 0; bo < size; bo++) { + val <<= 1; + const std::size_t bit = offs + bo; + val |= (data[bit / 8] >> (7 - (bit % 8))) & 0x01; + } + } + return val; +} + +// --------------------------------------------------------------------------------------------------------------------- + +int64_t Rtcm3GetSigned(const uint8_t* data, const std::size_t offs, const std::size_t size) +{ + uint64_t val = 0; + if ((data != NULL) && (size > 0)) { + for (std::size_t bo = 0; bo < size; bo++) { + val <<= 1; + const std::size_t bit = offs + bo; + val |= (data[bit / 8] >> (7 - (bit % 8))) & 0x01; + } + // Sign-extend to full 64 bits + if ((val & ((uint64_t)1 << (size - 1))) != 0) { + for (std::size_t bo = size; bo < 64; bo++) { + val |= (uint64_t)1 << bo; + } + } + } + return (int64_t)val; +} + +// --------------------------------------------------------------------------------------------------------------------- + +std::size_t Rtcm3CountBits(const uint64_t mask) +{ + std::size_t cnt = 0; + for (uint64_t m = mask; m != 0; m >>= 1) { + if ((m & 0x1) != 0) { + cnt++; + } + } + return cnt; +} + +// --------------------------------------------------------------------------------------------------------------------- + +bool Rtcm3GetArp(const uint8_t* msg, Rtcm3Arp& arp) +{ + bool ok = false; + if (msg != NULL) { + const uint8_t* data = &msg[RTCM3_HEAD_SIZE]; + const uint16_t msg_type = Rtcm3Type(msg); + switch (msg_type) { // clang-format off + case RTCM3_TYPE1005_MSGID: /* FALLTHROUGH */ + case RTCM3_TYPE1006_MSGID: + arp.ref_sta_id_ = Rtcm3GetUnsigned(data, 12, 12); // DF003 + arp.ecef_x_ = (double)Rtcm3GetSigned(data, 34, 38) * 0.0001; // DF025 + arp.ecef_y_ = (double)Rtcm3GetSigned(data, 74, 38) * 0.0001; // DF026 + arp.ecef_z_ = (double)Rtcm3GetSigned(data, 114, 38) * 0.0001; // DF027 + ok = true; + break; + case RTCM3_TYPE1032_MSGID: + arp.ref_sta_id_ = Rtcm3GetUnsigned(data, 12, 12); // DF003 + arp.ecef_x_ = (double)Rtcm3GetSigned(data, 42, 38) * 0.0001; // DF025 + arp.ecef_y_ = (double)Rtcm3GetSigned(data, 80, 38) * 0.0001; // DF026 + arp.ecef_z_ = (double)Rtcm3GetSigned(data, 118, 38) * 0.0001; // DF027 + ok = true; + break; + } // clang-format on + } + return ok; +} + +// --------------------------------------------------------------------------------------------------------------------- + +bool Rtcm3GetAnt(const uint8_t* msg, Rtcm3Ant& ant) +{ + bool ok = false; + if (msg != NULL) { + const uint8_t* data = &msg[RTCM3_HEAD_SIZE]; + const uint16_t msg_type = Rtcm3Type(msg); + if ((msg_type == RTCM3_TYPE1007_MSGID) || (msg_type == RTCM3_TYPE1008_MSGID) || + (msg_type == RTCM3_TYPE1033_MSGID)) { + std::memset(&ant, 0, sizeof(ant)); + + int offs = 12; + ant.ref_sta_id_ = Rtcm3GetUnsigned(data, offs, 12); // DF003 + offs += 12; + const int n = Rtcm3GetUnsigned(data, offs, 8); // DF029 + offs += 8; + for (int ix = 0; (ix < n) && (ix < ((int)sizeof(ant.ant_desc_) - 1)); ix++) { + ant.ant_desc_[ix] = Rtcm3GetUnsigned(data, offs, 8); // DF030 + offs += 8; + } + ant.ant_setup_id_ = Rtcm3GetUnsigned(data, offs, 8); // DF031 + offs += 8; + if ((msg_type == RTCM3_TYPE1008_MSGID) || (msg_type == RTCM3_TYPE1033_MSGID)) { + const int m = Rtcm3GetUnsigned(data, offs, 8); // DF032 + offs += 8; + for (int ix = 0; (ix < m) && (ix < ((int)sizeof(ant.ant_serial_) - 1)); ix++) { + ant.ant_serial_[ix] = Rtcm3GetUnsigned(data, offs, 8); // DF033 + offs += 8; + } + } + + if (msg_type == RTCM3_TYPE1033_MSGID) { + const int i = Rtcm3GetUnsigned(data, offs, 8); // DF227 + offs += 8; + for (int ix = 0; (ix < i) && (ix < ((int)sizeof(ant.rx_type_) - 1)); ix++) { + ant.rx_type_[ix] = Rtcm3GetUnsigned(data, offs, 8); // DF228 + offs += 8; + } + const int j = Rtcm3GetUnsigned(data, offs, 8); // DF229 + offs += 8; + for (int ix = 0; (ix < j) && (ix < ((int)sizeof(ant.rx_fw_) - 1)); ix++) { + ant.rx_fw_[ix] = Rtcm3GetUnsigned(data, offs, 8); // DF230 + offs += 8; + } + const int k = Rtcm3GetUnsigned(data, offs, 8); // DF231 + offs += 8; + for (int ix = 0; (ix < k) && (ix < ((int)sizeof(ant.rx_serial_) - 1)); ix++) { + ant.rx_serial_[ix] = Rtcm3GetUnsigned(data, offs, 8); // DF232 + offs += 8; + } + } + + ok = true; + } + } + return ok; +} + +// --------------------------------------------------------------------------------------------------------------------- + +bool Rtcm3TypeToMsm(uint16_t msg_type, Rtcm3MsmGnss& gnss, Rtcm3MsmType& msm) +{ + const uint16_t gnss_val = ((msg_type - 1000) / 10) * 10; + const uint16_t msm_val = msg_type % 10; + if ( + // MSM1-7 + (msm_val >= types::EnumToVal(Rtcm3MsmType::MSM1)) && (msm_val <= types::EnumToVal(Rtcm3MsmType::MSM7)) && + // One of the known GNSS + ((gnss_val == types::EnumToVal(Rtcm3MsmGnss::GPS)) || (gnss_val == types::EnumToVal(Rtcm3MsmGnss::GLO)) || + (gnss_val == types::EnumToVal(Rtcm3MsmGnss::GAL)) || (gnss_val == types::EnumToVal(Rtcm3MsmGnss::SBAS)) || + (gnss_val == types::EnumToVal(Rtcm3MsmGnss::QZSS)) || (gnss_val == types::EnumToVal(Rtcm3MsmGnss::BDS)) || + (gnss_val == types::EnumToVal(Rtcm3MsmGnss::NAVIC)))) { + msm = (Rtcm3MsmType)msm_val; + gnss = (Rtcm3MsmGnss)gnss_val; + return true; + } else { + return false; + } +} + +// --------------------------------------------------------------------------------------------------------------------- + +bool Rtcm3GetMsmHeader(const uint8_t* msg, Rtcm3MsmHeader& header) +{ + if (msg == NULL) { + return false; + } + const uint16_t msg_type = Rtcm3Type(msg); + if (!Rtcm3TypeToMsm(msg_type, header.gnss_, header.msm_)) { + return false; // Not an MSM message + } + header.msg_type_ = msg_type; + + const uint8_t* data = &msg[RTCM3_HEAD_SIZE]; + header.ref_sta_id_ = Rtcm3GetUnsigned(data, 12, 12); // DF003 + if (header.gnss_ == Rtcm3MsmGnss::GLO) { + const int dow = Rtcm3GetUnsigned(data, 24, 3); // DF416 + const int tod = Rtcm3GetUnsigned(data, 27, 27); // DF034 + header.glo_tow_ = ((double)dow * 86400.0) + ((double)tod * 1e-3); + } else { + header.any_tow_ = (double)Rtcm3GetUnsigned(data, 24, 30) * 1e-3; // DF004, DF416, DF248, DF427 + } + // clang-format off + header.multi_msg_bit_ = Rtcm3GetUnsigned(data, 54, 1); // DF393 + header.iods_ = Rtcm3GetUnsigned(data, 55, 3); // DF409 + // bit(7) reserved // DF001 + header.clk_steering_ = Rtcm3GetUnsigned(data, 65, 2); // DF411 + header.ext_clock_ = Rtcm3GetUnsigned(data, 67, 2); // DF412 + header.smooth_ = Rtcm3GetUnsigned(data, 69, 1); // DF417 + header.smooth_int_ = Rtcm3GetUnsigned(data, 70, 3); // DF418 + header.sat_mask_ = Rtcm3GetUnsigned(data, 73, 64); // DF394 + header.sig_mask_ = Rtcm3GetUnsigned(data, 137, 32); // DF395 + header.num_sat_ = Rtcm3CountBits(header.sat_mask_); + header.num_sig_ = Rtcm3CountBits(header.sig_mask_); + header.num_cell_ = header.num_sat_ * header.num_sig_; + header.cell_mask_ = Rtcm3GetUnsigned(data, 169, header.num_cell_); // DF396 + // clang-format on + + return true; +} + +// --------------------------------------------------------------------------------------------------------------------- + +bool Rtcm3GetMessageInfo(char* info, const std::size_t size, const uint8_t* msg, const std::size_t msg_size) +{ + if ((info == NULL) || (size < 1)) { + return false; + } + + if ((msg == NULL) || (msg_size < (RTCM3_HEAD_SIZE + 2))) { + info[0] = '\0'; + return false; + } + std::size_t len = 0; + + Rtcm3Arp arp; + if ((len < size) && Rtcm3GetArp(msg, arp)) { + len = std::snprintf(info, size, "(#%d) %.2f %.2f %.2f", arp.ref_sta_id_, arp.ecef_x_, arp.ecef_y_, arp.ecef_z_); + } + + Rtcm3Ant ant; + if ((len < size) && Rtcm3GetAnt(msg, ant)) { + len = std::snprintf(info, size, "(#%d) [%s] [%s] %" PRIu8 " [%s] [%s] [%s]", ant.ref_sta_id_, ant.ant_desc_, + ant.ant_serial_, ant.ant_setup_id_, ant.rx_type_, ant.rx_fw_, ant.rx_serial_); + } + + Rtcm3MsmHeader msm; + if ((len < size) && Rtcm3GetMsmHeader(msg, msm)) { + len = snprintf(info, size, "(#%d) %010.3f (%d * %d, %s)", msm.ref_sta_id_, msm.any_tow_, msm.num_sat_, + msm.num_sig_, msm.multi_msg_bit_ ? "more" : "last"); + } + + const char* type_desc = Rtcm3GetTypeDesc(Rtcm3Type(msg)); + if ((len < size) && (type_desc != NULL)) { + len += snprintf(&info[len], size - len, "%s%s", len > 0 ? " - " : "", type_desc); + } + + return (len > 0) && (len < size); +} + +/* ****************************************************************************************************************** */ +} // namespace rtcm3 +} // namespace parser +} // namespace common +} // namespace fpsdk diff --git a/fpsdk_common/src/parser/spartn.cpp b/fpsdk_common/src/parser/spartn.cpp new file mode 100644 index 0000000..1a1d6f8 --- /dev/null +++ b/fpsdk_common/src/parser/spartn.cpp @@ -0,0 +1,163 @@ +/** + * \verbatim + * ___ ___ + * \ \ / / + * \ \/ / Copyright (c) Fixposition AG (www.fixposition.com) and contributors + * / /\ \ License: see the LICENSE file + * /__/ \__\ + * + * Based on work by flipflip (https://github.com/phkehl) + * \endverbatim + * + * @file + * @brief Fixposition SDK: Parser SPARTN routines and types + */ + +/* LIBC/STL */ +#include +#include +#include +#include + +/* EXTERNAL */ + +/* PACKAGE */ +#include "fpsdk_common/parser/spartn.hpp" + +namespace fpsdk { +namespace common { +namespace parser { +namespace spartn { +/* ****************************************************************************************************************** */ + +// Lookup table entry +struct MsgInfo +{ + uint8_t msg_type_; + uint8_t sub_type_; + const char* name_; + const char* desc_; +}; + +// clang-format off +// @fp_codegen_begin{FPSDK_COMMON_PARSER_SPARTN_MSGINFO} +static constexpr std::array MSG_INFO = +{{ + { SPARTN_OCB_MSGID, 0, SPARTN_OCB_STRID, "Orbits, clock, bias (OCB)" }, + { SPARTN_HPAC_MSGID, 0, SPARTN_HPAC_STRID, "High-precision atmosphere correction (HPAC)" }, + { SPARTN_GAD_MSGID, 0, SPARTN_GAD_STRID, "Geographic area definition (GAD)" }, + { SPARTN_BPAC_MSGID, 0, SPARTN_BPAC_STRID, "Basic-precision atmosphere correction (BPAC)" }, + { SPARTN_EAS_MSGID, 0, SPARTN_EAS_STRID, "Encryption and authentication support (EAS)" }, + { SPARTN_PROP_MSGID, 0, SPARTN_PROP_STRID, "Proprietary message" }, +}}; +static constexpr std::array SUB_INFO = +{{ + { SPARTN_OCB_MSGID, SPARTN_OCB_GPS_SUBID, SPARTN_OCB_GPS_STRID, "Orbits, clock, bias (OCB) GPS" }, + { SPARTN_OCB_MSGID, SPARTN_OCB_GLO_SUBID, SPARTN_OCB_GLO_STRID, "Orbits, clock, bias (OCB) GLONASS" }, + { SPARTN_OCB_MSGID, SPARTN_OCB_GAL_SUBID, SPARTN_OCB_GAL_STRID, "Orbits, clock, bias (OCB) Galileo" }, + { SPARTN_OCB_MSGID, SPARTN_OCB_BDS_SUBID, SPARTN_OCB_BDS_STRID, "Orbits, clock, bias (OCB) BeiDou" }, + { SPARTN_OCB_MSGID, SPARTN_OCB_QZSS_SUBID, SPARTN_OCB_QZSS_STRID, "Orbits, clock, bias (OCB) QZSS" }, + { SPARTN_HPAC_MSGID, SPARTN_HPAC_GPS_SUBID, SPARTN_HPAC_GPS_STRID, "High-precision atmosphere correction (HPAC) GPS" }, + { SPARTN_HPAC_MSGID, SPARTN_HPAC_GLO_SUBID, SPARTN_HPAC_GLO_STRID, "High-precision atmosphere correction (HPAC) GLONASS" }, + { SPARTN_HPAC_MSGID, SPARTN_HPAC_GAL_SUBID, SPARTN_HPAC_GAL_STRID, "High-precision atmosphere correction (HPAC) Galileo" }, + { SPARTN_HPAC_MSGID, SPARTN_HPAC_BDS_SUBID, SPARTN_HPAC_BDS_STRID, "High-precision atmosphere correction (HPAC) BeiDou" }, + { SPARTN_HPAC_MSGID, SPARTN_HPAC_QZSS_SUBID, SPARTN_HPAC_QZSS_STRID, "High-precision atmosphere correction (HPAC) QZSS" }, + { SPARTN_GAD_MSGID, SPARTN_GAD_GAD_SUBID, SPARTN_GAD_GAD_STRID, "Geographic area definition (GAD)" }, + { SPARTN_BPAC_MSGID, SPARTN_BPAC_POLY_SUBID, SPARTN_BPAC_POLY_STRID, "Basic-precision atmosphere correction (BPAC)" }, + { SPARTN_EAS_MSGID, SPARTN_EAS_KEY_SUBID, SPARTN_EAS_KEY_STRID, "Encryption and authentication support (EAS): Dynamic key" }, + { SPARTN_EAS_MSGID, SPARTN_EAS_GROUP_SUBID, SPARTN_EAS_GROUP_STRID, "Encryption and authentication support (EAS): Group authentication" }, + { SPARTN_PROP_MSGID, SPARTN_PROP_EST_SUBID, SPARTN_PROP_EST_STRID, "Proprietary messages: test" }, + { SPARTN_PROP_MSGID, SPARTN_PROP_UBLOX_SUBID, SPARTN_PROP_UBLOX_STRID, "Proprietary messages: u-blox" }, + { SPARTN_PROP_MSGID, SPARTN_PROP_SWIFT_SUBID, SPARTN_PROP_SWIFT_STRID, "Proprietary messages: Swift" }, +}}; +// @fp_codegen_end{FPSDK_COMMON_PARSER_SPARTN_MSGINFO} +// clang-format on + +bool SpartnGetMessageName(char* name, const std::size_t size, const uint8_t* msg, const std::size_t msg_size) +{ + // Check arguments + if ((name == NULL) || (size < 1)) { + return false; + } + name[0] = '\0'; + + if ((msg == NULL) || (msg_size < (SPARTN_MIN_HEAD_SIZE + 2))) { + return false; + } + + const uint8_t msg_type = SpartnType(msg); + const uint8_t sub_type = SpartnSubType(msg); + + std::size_t res = 0; + + // First try the message name lookup table + for (auto& info : SUB_INFO) { + if ((info.msg_type_ == msg_type) && (info.sub_type_ == sub_type)) { + res = snprintf(name, size, "%s", info.name_); + break; + } + } + + // If that failed, try the class name lookup table + if (res == 0) { + for (auto& info : MSG_INFO) { + if (info.msg_type_ == msg_type) { + res = snprintf(name, size, "%s-%-" PRIu8, info.name_, sub_type); + break; + } + } + } + + // If that failed, too, stringify both types + if (res == 0) { + res = snprintf(name, size, "SPARTN-%" PRIu8 "-%" PRIu8, msg_type, sub_type); + } + + // Did it fit into the string? + return res < size; +} + +// --------------------------------------------------------------------------------------------------------------------- + +const char* SpartnGetTypeDesc(const uint16_t type, const uint16_t subtype) +{ + for (auto& info : SUB_INFO) { + if ((info.msg_type_ == type) && (info.sub_type_ == subtype)) { + return info.desc_; + } + } + for (auto& info : MSG_INFO) { + if (info.msg_type_ == type) { + return info.desc_; + } + } + return NULL; +} + +// --------------------------------------------------------------------------------------------------------------------- + +bool SpartnGetMessageInfo(char* info, const std::size_t size, const uint8_t* msg, const std::size_t msg_size) +{ + if ((info == NULL) || (size < 1)) { + return false; + } + + if ((msg == NULL) || (msg_size < SPARTN_MIN_HEAD_SIZE)) { + info[0] = '\0'; + return false; + } + std::size_t len = 0; + + const char* type_desc = SpartnGetTypeDesc(SpartnType(msg), SpartnSubType(msg)); + if ((len < size) && (type_desc != NULL)) { + len += snprintf(&info[len], size - len, "%s%s", len > 0 ? " - " : "", type_desc); + } + + return (len > 0) && (len < size); +} + +/* ****************************************************************************************************************** */ +} // namespace spartn +} // namespace parser +} // namespace common +} // namespace fpsdk diff --git a/fpsdk_common/src/parser/types.cpp b/fpsdk_common/src/parser/types.cpp new file mode 100644 index 0000000..5ed13e8 --- /dev/null +++ b/fpsdk_common/src/parser/types.cpp @@ -0,0 +1,129 @@ +/** + * \verbatim + * ___ ___ + * \ \ / / + * \ \/ / Copyright (c) Fixposition AG (www.fixposition.com) and contributors + * / /\ \ License: see the LICENSE file + * /__/ \__\ + * + * Based on work by flipflip (https://github.com/phkehl) + * \endverbatim + * + * @file + * @brief Fixposition SDK: Parser types + */ + +/* LIBC/STL */ +#include +#include + +/* EXTERNAL */ + +/* PACKAGE */ +#include "fpsdk_common/parser/fpa.hpp" +#include "fpsdk_common/parser/fpb.hpp" +#include "fpsdk_common/parser/nmea.hpp" +#include "fpsdk_common/parser/novb.hpp" +#include "fpsdk_common/parser/rtcm3.hpp" +#include "fpsdk_common/parser/spartn.hpp" +#include "fpsdk_common/parser/types.hpp" +#include "fpsdk_common/parser/ubx.hpp" +#include "fpsdk_common/parser/unib.hpp" + +namespace fpsdk { +namespace common { +namespace parser { +/* ****************************************************************************************************************** */ + +const char* ProtocolStr(const Protocol proto) +{ + switch (proto) { // clang-format off + case Protocol::FP_A: return PROTOCOL_NAME_FP_A; + case Protocol::FP_B: return PROTOCOL_NAME_FP_B; + case Protocol::NMEA: return PROTOCOL_NAME_NMEA; + case Protocol::UBX: return PROTOCOL_NAME_UBX; + case Protocol::RTCM3: return PROTOCOL_NAME_RTCM3; + case Protocol::UNI_B: return PROTOCOL_NAME_UNI_B; + case Protocol::NOV_B: return PROTOCOL_NAME_NOV_B; + case Protocol::SPARTN: return PROTOCOL_NAME_SPARTN; + case Protocol::OTHER: return PROTOCOL_NAME_OTHER; + } // clang-format on + return "?"; +} + +// --------------------------------------------------------------------------------------------------------------------- + +Protocol StrProtocol(const char* name) +{ + if (name != NULL) { // clang-format off + if (std::strcmp(name, PROTOCOL_NAME_FP_A) == 0) { return Protocol::FP_A; } + else if (std::strcmp(name, PROTOCOL_NAME_FP_B) == 0) { return Protocol::FP_B; } + else if (std::strcmp(name, PROTOCOL_NAME_NMEA) == 0) { return Protocol::NMEA; } + else if (std::strcmp(name, PROTOCOL_NAME_UBX) == 0) { return Protocol::UBX; } + else if (std::strcmp(name, PROTOCOL_NAME_RTCM3) == 0) { return Protocol::RTCM3; } + else if (std::strcmp(name, PROTOCOL_NAME_UNI_B) == 0) { return Protocol::UNI_B; } + else if (std::strcmp(name, PROTOCOL_NAME_NOV_B) == 0) { return Protocol::NOV_B; } + else if (std::strcmp(name, PROTOCOL_NAME_SPARTN) == 0) { return Protocol::SPARTN; } + } // clang-format on + return Protocol::OTHER; +} +// --------------------------------------------------------------------------------------------------------------------- + +void ParserMsg::MakeInfo() const +{ + if (!info_.empty()) { + return; + } + char sinfo[MAX_INFO_SIZE]; + const uint8_t* mdata = data_.data(); + const int msize = (int)data_.size(); + switch (proto_) { + case Protocol::FP_A: + info_ = (fpa::FpaGetMessageInfo(sinfo, sizeof(sinfo), mdata, msize) ? sinfo : ""); + break; + case Protocol::FP_B: + info_ = (fpb::FpbGetMessageInfo(sinfo, sizeof(sinfo), mdata, msize) ? sinfo : ""); + break; + case Protocol::NMEA: + info_ = (nmea::NmeaGetMessageInfo(sinfo, sizeof(sinfo), mdata, msize) ? sinfo : ""); + break; + case Protocol::UBX: + info_ = (ubx::UbxGetMessageInfo(sinfo, sizeof(sinfo), mdata, msize) ? sinfo : ""); + break; + case Protocol::RTCM3: + info_ = (rtcm3::Rtcm3GetMessageInfo(sinfo, sizeof(sinfo), mdata, msize) ? sinfo : ""); + break; + case Protocol::UNI_B: + info_ = (unib::UnibGetMessageInfo(sinfo, sizeof(sinfo), mdata, msize) ? sinfo : ""); + break; + case Protocol::NOV_B: + info_ = (novb::NovbGetMessageInfo(sinfo, sizeof(sinfo), mdata, msize) ? sinfo : ""); + break; + case Protocol::SPARTN: + info_ = (spartn::SpartnGetMessageInfo(sinfo, sizeof(sinfo), mdata, msize) ? sinfo : ""); + break; + case Protocol::OTHER: { + // Info is a hexdump of the first few bytes + constexpr int num = 16; + sinfo[0] = '\0'; + for (int ix = 0; (ix < num) && (ix < msize); ix++) { + std::snprintf(&sinfo[ix * 3], sizeof(sinfo - (ix * 3)), "%02x ", mdata[ix]); + } + if (msize > 16) { + sinfo[(num * 3) + 0] = '.'; + sinfo[(num * 3) + 1] = '.'; + sinfo[(num * 3) + 2] = '.'; + sinfo[(num * 3) + 3] = '\0'; + } else { + sinfo[num * 3] = '\0'; + } + info_ = sinfo; + break; + } + } +} + +/* ****************************************************************************************************************** */ +} // namespace parser +} // namespace common +} // namespace fpsdk diff --git a/fpsdk_common/src/parser/ubx.cpp b/fpsdk_common/src/parser/ubx.cpp new file mode 100644 index 0000000..60531fd --- /dev/null +++ b/fpsdk_common/src/parser/ubx.cpp @@ -0,0 +1,1066 @@ +/** + * \verbatim + * ___ ___ + * \ \ / / + * \ \/ / Copyright (c) Fixposition AG (www.fixposition.com) and contributors + * / /\ \ License: see the LICENSE file + * /__/ \__\ + * + * Based on work by flipflip (https://github.com/phkehl) + * \endverbatim + * + * @file + * @brief Fixposition SDK: Parser UBX routines and types + */ + +/* LIBC/STL */ +#include +#include +#include +#include +#include +#include +#include + +/* EXTERNAL */ + +/* PACKAGE */ +#include "fpsdk_common/gnss.hpp" +#include "fpsdk_common/math.hpp" +#include "fpsdk_common/parser/crc.hpp" +#include "fpsdk_common/parser/types.hpp" +#include "fpsdk_common/parser/ubx.hpp" + +namespace fpsdk { +namespace common { +namespace parser { +namespace ubx { +/* ****************************************************************************************************************** */ + +// clang-format off +// @fp_codegen_begin{FPSDK_COMMON_PARSER_UBX_MSGINFO_CPP} +static const UbxClassesInfo CLS_INFO = +{{ + { UBX_ACK_CLSID, 0x00, UBX_ACK_STRID }, + { UBX_CFG_CLSID, 0x00, UBX_CFG_STRID }, + { UBX_ESF_CLSID, 0x00, UBX_ESF_STRID }, + { UBX_INF_CLSID, 0x00, UBX_INF_STRID }, + { UBX_LOG_CLSID, 0x00, UBX_LOG_STRID }, + { UBX_MGA_CLSID, 0x00, UBX_MGA_STRID }, + { UBX_MON_CLSID, 0x00, UBX_MON_STRID }, + { UBX_NAV_CLSID, 0x00, UBX_NAV_STRID }, + { UBX_NAV2_CLSID, 0x00, UBX_NAV2_STRID }, + { UBX_RXM_CLSID, 0x00, UBX_RXM_STRID }, + { UBX_SEC_CLSID, 0x00, UBX_SEC_STRID }, + { UBX_TIM_CLSID, 0x00, UBX_TIM_STRID }, + { UBX_UPD_CLSID, 0x00, UBX_UPD_STRID }, + { UBX_NMEA_CLSID, 0x00, UBX_NMEA_STRID }, + { UBX_RTCM3_CLSID, 0x00, UBX_RTCM3_STRID }, +}}; +static const UbxMessagesInfo MSG_INFO = +{{ + { UBX_ACK_CLSID, UBX_ACK_ACK_MSGID, UBX_ACK_ACK_STRID }, + { UBX_ACK_CLSID, UBX_ACK_NAK_MSGID, UBX_ACK_NAK_STRID }, + { UBX_CFG_CLSID, UBX_CFG_CFG_MSGID, UBX_CFG_CFG_STRID }, + { UBX_CFG_CLSID, UBX_CFG_PWR_MSGID, UBX_CFG_PWR_STRID }, + { UBX_CFG_CLSID, UBX_CFG_RST_MSGID, UBX_CFG_RST_STRID }, + { UBX_CFG_CLSID, UBX_CFG_VALDEL_MSGID, UBX_CFG_VALDEL_STRID }, + { UBX_CFG_CLSID, UBX_CFG_VALGET_MSGID, UBX_CFG_VALGET_STRID }, + { UBX_CFG_CLSID, UBX_CFG_VALSET_MSGID, UBX_CFG_VALSET_STRID }, + { UBX_ESF_CLSID, UBX_ESF_ALG_MSGID, UBX_ESF_ALG_STRID }, + { UBX_ESF_CLSID, UBX_ESF_INS_MSGID, UBX_ESF_INS_STRID }, + { UBX_ESF_CLSID, UBX_ESF_MEAS_MSGID, UBX_ESF_MEAS_STRID }, + { UBX_ESF_CLSID, UBX_ESF_RAW_MSGID, UBX_ESF_RAW_STRID }, + { UBX_ESF_CLSID, UBX_ESF_STATUS_MSGID, UBX_ESF_STATUS_STRID }, + { UBX_INF_CLSID, UBX_INF_DEBUG_MSGID, UBX_INF_DEBUG_STRID }, + { UBX_INF_CLSID, UBX_INF_ERROR_MSGID, UBX_INF_ERROR_STRID }, + { UBX_INF_CLSID, UBX_INF_NOTICE_MSGID, UBX_INF_NOTICE_STRID }, + { UBX_INF_CLSID, UBX_INF_TEST_MSGID, UBX_INF_TEST_STRID }, + { UBX_INF_CLSID, UBX_INF_WARNING_MSGID, UBX_INF_WARNING_STRID }, + { UBX_LOG_CLSID, UBX_LOG_CREATE_MSGID, UBX_LOG_CREATE_STRID }, + { UBX_LOG_CLSID, UBX_LOG_ERASE_MSGID, UBX_LOG_ERASE_STRID }, + { UBX_LOG_CLSID, UBX_LOG_FINDTIME_MSGID, UBX_LOG_FINDTIME_STRID }, + { UBX_LOG_CLSID, UBX_LOG_INFO_MSGID, UBX_LOG_INFO_STRID }, + { UBX_LOG_CLSID, UBX_LOG_RETR_MSGID, UBX_LOG_RETR_STRID }, + { UBX_LOG_CLSID, UBX_LOG_RETRPOS_MSGID, UBX_LOG_RETRPOS_STRID }, + { UBX_LOG_CLSID, UBX_LOG_RETRPOSX_MSGID, UBX_LOG_RETRPOSX_STRID }, + { UBX_LOG_CLSID, UBX_LOG_RETRSTR_MSGID, UBX_LOG_RETRSTR_STRID }, + { UBX_LOG_CLSID, UBX_LOG_STR_MSGID, UBX_LOG_STR_STRID }, + { UBX_MGA_CLSID, UBX_MGA_ACK_MSGID, UBX_MGA_ACK_STRID }, + { UBX_MGA_CLSID, UBX_MGA_BDS_MSGID, UBX_MGA_BDS_STRID }, + { UBX_MGA_CLSID, UBX_MGA_DBD_MSGID, UBX_MGA_DBD_STRID }, + { UBX_MGA_CLSID, UBX_MGA_GAL_MSGID, UBX_MGA_GAL_STRID }, + { UBX_MGA_CLSID, UBX_MGA_GLO_MSGID, UBX_MGA_GLO_STRID }, + { UBX_MGA_CLSID, UBX_MGA_GPS_MSGID, UBX_MGA_GPS_STRID }, + { UBX_MGA_CLSID, UBX_MGA_INI_MSGID, UBX_MGA_INI_STRID }, + { UBX_MGA_CLSID, UBX_MGA_QZSS_MSGID, UBX_MGA_QZSS_STRID }, + { UBX_MON_CLSID, UBX_MON_COMMS_MSGID, UBX_MON_COMMS_STRID }, + { UBX_MON_CLSID, UBX_MON_GNSS_MSGID, UBX_MON_GNSS_STRID }, + { UBX_MON_CLSID, UBX_MON_HW_MSGID, UBX_MON_HW_STRID }, + { UBX_MON_CLSID, UBX_MON_HW2_MSGID, UBX_MON_HW2_STRID }, + { UBX_MON_CLSID, UBX_MON_HW3_MSGID, UBX_MON_HW3_STRID }, + { UBX_MON_CLSID, UBX_MON_IO_MSGID, UBX_MON_IO_STRID }, + { UBX_MON_CLSID, UBX_MON_MSGPP_MSGID, UBX_MON_MSGPP_STRID }, + { UBX_MON_CLSID, UBX_MON_PATCH_MSGID, UBX_MON_PATCH_STRID }, + { UBX_MON_CLSID, UBX_MON_RF_MSGID, UBX_MON_RF_STRID }, + { UBX_MON_CLSID, UBX_MON_RXBUF_MSGID, UBX_MON_RXBUF_STRID }, + { UBX_MON_CLSID, UBX_MON_RXR_MSGID, UBX_MON_RXR_STRID }, + { UBX_MON_CLSID, UBX_MON_SPAN_MSGID, UBX_MON_SPAN_STRID }, + { UBX_MON_CLSID, UBX_MON_SYS_MSGID, UBX_MON_SYS_STRID }, + { UBX_MON_CLSID, UBX_MON_TEMP_MSGID, UBX_MON_TEMP_STRID }, + { UBX_MON_CLSID, UBX_MON_TXBUF_MSGID, UBX_MON_TXBUF_STRID }, + { UBX_MON_CLSID, UBX_MON_VER_MSGID, UBX_MON_VER_STRID }, + { UBX_NAV_CLSID, UBX_NAV_ATT_MSGID, UBX_NAV_ATT_STRID }, + { UBX_NAV_CLSID, UBX_NAV_CLOCK_MSGID, UBX_NAV_CLOCK_STRID }, + { UBX_NAV_CLSID, UBX_NAV_COV_MSGID, UBX_NAV_COV_STRID }, + { UBX_NAV_CLSID, UBX_NAV_DOP_MSGID, UBX_NAV_DOP_STRID }, + { UBX_NAV_CLSID, UBX_NAV_EELL_MSGID, UBX_NAV_EELL_STRID }, + { UBX_NAV_CLSID, UBX_NAV_EOE_MSGID, UBX_NAV_EOE_STRID }, + { UBX_NAV_CLSID, UBX_NAV_GEOFENCE_MSGID, UBX_NAV_GEOFENCE_STRID }, + { UBX_NAV_CLSID, UBX_NAV_HPPOSECEF_MSGID, UBX_NAV_HPPOSECEF_STRID }, + { UBX_NAV_CLSID, UBX_NAV_HPPOSLLH_MSGID, UBX_NAV_HPPOSLLH_STRID }, + { UBX_NAV_CLSID, UBX_NAV_ODO_MSGID, UBX_NAV_ODO_STRID }, + { UBX_NAV_CLSID, UBX_NAV_ORB_MSGID, UBX_NAV_ORB_STRID }, + { UBX_NAV_CLSID, UBX_NAV_PL_MSGID, UBX_NAV_PL_STRID }, + { UBX_NAV_CLSID, UBX_NAV_POSECEF_MSGID, UBX_NAV_POSECEF_STRID }, + { UBX_NAV_CLSID, UBX_NAV_POSLLH_MSGID, UBX_NAV_POSLLH_STRID }, + { UBX_NAV_CLSID, UBX_NAV_PVAT_MSGID, UBX_NAV_PVAT_STRID }, + { UBX_NAV_CLSID, UBX_NAV_PVT_MSGID, UBX_NAV_PVT_STRID }, + { UBX_NAV_CLSID, UBX_NAV_RELPOSNED_MSGID, UBX_NAV_RELPOSNED_STRID }, + { UBX_NAV_CLSID, UBX_NAV_RESETODO_MSGID, UBX_NAV_RESETODO_STRID }, + { UBX_NAV_CLSID, UBX_NAV_SAT_MSGID, UBX_NAV_SAT_STRID }, + { UBX_NAV_CLSID, UBX_NAV_SBAS_MSGID, UBX_NAV_SBAS_STRID }, + { UBX_NAV_CLSID, UBX_NAV_SIG_MSGID, UBX_NAV_SIG_STRID }, + { UBX_NAV_CLSID, UBX_NAV_SLAS_MSGID, UBX_NAV_SLAS_STRID }, + { UBX_NAV_CLSID, UBX_NAV_STATUS_MSGID, UBX_NAV_STATUS_STRID }, + { UBX_NAV_CLSID, UBX_NAV_SVIN_MSGID, UBX_NAV_SVIN_STRID }, + { UBX_NAV_CLSID, UBX_NAV_TIMEBDS_MSGID, UBX_NAV_TIMEBDS_STRID }, + { UBX_NAV_CLSID, UBX_NAV_TIMEGAL_MSGID, UBX_NAV_TIMEGAL_STRID }, + { UBX_NAV_CLSID, UBX_NAV_TIMEGLO_MSGID, UBX_NAV_TIMEGLO_STRID }, + { UBX_NAV_CLSID, UBX_NAV_TIMEGPS_MSGID, UBX_NAV_TIMEGPS_STRID }, + { UBX_NAV_CLSID, UBX_NAV_TIMELS_MSGID, UBX_NAV_TIMELS_STRID }, + { UBX_NAV_CLSID, UBX_NAV_TIMEQZSS_MSGID, UBX_NAV_TIMEQZSS_STRID }, + { UBX_NAV_CLSID, UBX_NAV_TIMETRUSTED_MSGID, UBX_NAV_TIMETRUSTED_STRID }, + { UBX_NAV_CLSID, UBX_NAV_TIMEUTC_MSGID, UBX_NAV_TIMEUTC_STRID }, + { UBX_NAV_CLSID, UBX_NAV_VELECEF_MSGID, UBX_NAV_VELECEF_STRID }, + { UBX_NAV_CLSID, UBX_NAV_VELNED_MSGID, UBX_NAV_VELNED_STRID }, + { UBX_NAV2_CLSID, UBX_NAV2_CLOCK_MSGID, UBX_NAV2_CLOCK_STRID }, + { UBX_NAV2_CLSID, UBX_NAV2_COV_MSGID, UBX_NAV2_COV_STRID }, + { UBX_NAV2_CLSID, UBX_NAV2_DOP_MSGID, UBX_NAV2_DOP_STRID }, + { UBX_NAV2_CLSID, UBX_NAV2_EOE_MSGID, UBX_NAV2_EOE_STRID }, + { UBX_NAV2_CLSID, UBX_NAV2_ODO_MSGID, UBX_NAV2_ODO_STRID }, + { UBX_NAV2_CLSID, UBX_NAV2_POSECEF_MSGID, UBX_NAV2_POSECEF_STRID }, + { UBX_NAV2_CLSID, UBX_NAV2_POSLLH_MSGID, UBX_NAV2_POSLLH_STRID }, + { UBX_NAV2_CLSID, UBX_NAV2_PVT_MSGID, UBX_NAV2_PVT_STRID }, + { UBX_NAV2_CLSID, UBX_NAV2_SAT_MSGID, UBX_NAV2_SAT_STRID }, + { UBX_NAV2_CLSID, UBX_NAV2_SBAS_MSGID, UBX_NAV2_SBAS_STRID }, + { UBX_NAV2_CLSID, UBX_NAV2_SIG_MSGID, UBX_NAV2_SIG_STRID }, + { UBX_NAV2_CLSID, UBX_NAV2_SLAS_MSGID, UBX_NAV2_SLAS_STRID }, + { UBX_NAV2_CLSID, UBX_NAV2_STATUS_MSGID, UBX_NAV2_STATUS_STRID }, + { UBX_NAV2_CLSID, UBX_NAV2_SVIN_MSGID, UBX_NAV2_SVIN_STRID }, + { UBX_NAV2_CLSID, UBX_NAV2_TIMEBDS_MSGID, UBX_NAV2_TIMEBDS_STRID }, + { UBX_NAV2_CLSID, UBX_NAV2_TIMEGAL_MSGID, UBX_NAV2_TIMEGAL_STRID }, + { UBX_NAV2_CLSID, UBX_NAV2_TIMEGLO_MSGID, UBX_NAV2_TIMEGLO_STRID }, + { UBX_NAV2_CLSID, UBX_NAV2_TIMEGPS_MSGID, UBX_NAV2_TIMEGPS_STRID }, + { UBX_NAV2_CLSID, UBX_NAV2_TIMELS_MSGID, UBX_NAV2_TIMELS_STRID }, + { UBX_NAV2_CLSID, UBX_NAV2_TIMEQZSS_MSGID, UBX_NAV2_TIMEQZSS_STRID }, + { UBX_NAV2_CLSID, UBX_NAV2_TIMEUTC_MSGID, UBX_NAV2_TIMEUTC_STRID }, + { UBX_NAV2_CLSID, UBX_NAV2_VELECEF_MSGID, UBX_NAV2_VELECEF_STRID }, + { UBX_NAV2_CLSID, UBX_NAV2_VELNED_MSGID, UBX_NAV2_VELNED_STRID }, + { UBX_RXM_CLSID, UBX_RXM_COR_MSGID, UBX_RXM_COR_STRID }, + { UBX_RXM_CLSID, UBX_RXM_MEASX_MSGID, UBX_RXM_MEASX_STRID }, + { UBX_RXM_CLSID, UBX_RXM_PMP_MSGID, UBX_RXM_PMP_STRID }, + { UBX_RXM_CLSID, UBX_RXM_PMREQ_MSGID, UBX_RXM_PMREQ_STRID }, + { UBX_RXM_CLSID, UBX_RXM_QZSSL6_MSGID, UBX_RXM_QZSSL6_STRID }, + { UBX_RXM_CLSID, UBX_RXM_RAWX_MSGID, UBX_RXM_RAWX_STRID }, + { UBX_RXM_CLSID, UBX_RXM_RLM_MSGID, UBX_RXM_RLM_STRID }, + { UBX_RXM_CLSID, UBX_RXM_RTCM_MSGID, UBX_RXM_RTCM_STRID }, + { UBX_RXM_CLSID, UBX_RXM_SFRBX_MSGID, UBX_RXM_SFRBX_STRID }, + { UBX_RXM_CLSID, UBX_RXM_SPARTN_MSGID, UBX_RXM_SPARTN_STRID }, + { UBX_RXM_CLSID, UBX_RXM_SPARTNKEY_MSGID, UBX_RXM_SPARTNKEY_STRID }, + { UBX_SEC_CLSID, UBX_SEC_OSNMA_MSGID, UBX_SEC_OSNMA_STRID }, + { UBX_SEC_CLSID, UBX_SEC_SIG_MSGID, UBX_SEC_SIG_STRID }, + { UBX_SEC_CLSID, UBX_SEC_SIGLOG_MSGID, UBX_SEC_SIGLOG_STRID }, + { UBX_SEC_CLSID, UBX_SEC_UNIQID_MSGID, UBX_SEC_UNIQID_STRID }, + { UBX_TIM_CLSID, UBX_TIM_TM2_MSGID, UBX_TIM_TM2_STRID }, + { UBX_TIM_CLSID, UBX_TIM_TP_MSGID, UBX_TIM_TP_STRID }, + { UBX_TIM_CLSID, UBX_TIM_VRFY_MSGID, UBX_TIM_VRFY_STRID }, + { UBX_UPD_CLSID, UBX_UPD_FLDET_MSGID, UBX_UPD_FLDET_STRID }, + { UBX_UPD_CLSID, UBX_UPD_POS_MSGID, UBX_UPD_POS_STRID }, + { UBX_UPD_CLSID, UBX_UPD_SAFEBOOT_MSGID, UBX_UPD_SAFEBOOT_STRID }, + { UBX_UPD_CLSID, UBX_UPD_SOS_MSGID, UBX_UPD_SOS_STRID }, + { UBX_NMEA_CLSID, UBX_NMEA_STANDARD_DTM_MSGID, UBX_NMEA_STANDARD_DTM_STRID }, + { UBX_NMEA_CLSID, UBX_NMEA_STANDARD_GAQ_MSGID, UBX_NMEA_STANDARD_GAQ_STRID }, + { UBX_NMEA_CLSID, UBX_NMEA_STANDARD_GBQ_MSGID, UBX_NMEA_STANDARD_GBQ_STRID }, + { UBX_NMEA_CLSID, UBX_NMEA_STANDARD_GBS_MSGID, UBX_NMEA_STANDARD_GBS_STRID }, + { UBX_NMEA_CLSID, UBX_NMEA_STANDARD_GGA_MSGID, UBX_NMEA_STANDARD_GGA_STRID }, + { UBX_NMEA_CLSID, UBX_NMEA_STANDARD_GLL_MSGID, UBX_NMEA_STANDARD_GLL_STRID }, + { UBX_NMEA_CLSID, UBX_NMEA_STANDARD_GLQ_MSGID, UBX_NMEA_STANDARD_GLQ_STRID }, + { UBX_NMEA_CLSID, UBX_NMEA_STANDARD_GNQ_MSGID, UBX_NMEA_STANDARD_GNQ_STRID }, + { UBX_NMEA_CLSID, UBX_NMEA_STANDARD_GNS_MSGID, UBX_NMEA_STANDARD_GNS_STRID }, + { UBX_NMEA_CLSID, UBX_NMEA_STANDARD_GPQ_MSGID, UBX_NMEA_STANDARD_GPQ_STRID }, + { UBX_NMEA_CLSID, UBX_NMEA_STANDARD_GQQ_MSGID, UBX_NMEA_STANDARD_GQQ_STRID }, + { UBX_NMEA_CLSID, UBX_NMEA_STANDARD_GRS_MSGID, UBX_NMEA_STANDARD_GRS_STRID }, + { UBX_NMEA_CLSID, UBX_NMEA_STANDARD_GSA_MSGID, UBX_NMEA_STANDARD_GSA_STRID }, + { UBX_NMEA_CLSID, UBX_NMEA_STANDARD_GST_MSGID, UBX_NMEA_STANDARD_GST_STRID }, + { UBX_NMEA_CLSID, UBX_NMEA_STANDARD_GSV_MSGID, UBX_NMEA_STANDARD_GSV_STRID }, + { UBX_NMEA_CLSID, UBX_NMEA_STANDARD_RLM_MSGID, UBX_NMEA_STANDARD_RLM_STRID }, + { UBX_NMEA_CLSID, UBX_NMEA_STANDARD_RMC_MSGID, UBX_NMEA_STANDARD_RMC_STRID }, + { UBX_NMEA_CLSID, UBX_NMEA_STANDARD_TXT_MSGID, UBX_NMEA_STANDARD_TXT_STRID }, + { UBX_NMEA_CLSID, UBX_NMEA_STANDARD_VLW_MSGID, UBX_NMEA_STANDARD_VLW_STRID }, + { UBX_NMEA_CLSID, UBX_NMEA_STANDARD_VTG_MSGID, UBX_NMEA_STANDARD_VTG_STRID }, + { UBX_NMEA_CLSID, UBX_NMEA_STANDARD_ZDA_MSGID, UBX_NMEA_STANDARD_ZDA_STRID }, + { UBX_NMEA_CLSID, UBX_NMEA_PUBX_CONFIG_MSGID, UBX_NMEA_PUBX_CONFIG_STRID }, + { UBX_NMEA_CLSID, UBX_NMEA_PUBX_POSITION_MSGID, UBX_NMEA_PUBX_POSITION_STRID }, + { UBX_NMEA_CLSID, UBX_NMEA_PUBX_RATE_MSGID, UBX_NMEA_PUBX_RATE_STRID }, + { UBX_NMEA_CLSID, UBX_NMEA_PUBX_SVSTATUS_MSGID, UBX_NMEA_PUBX_SVSTATUS_STRID }, + { UBX_NMEA_CLSID, UBX_NMEA_PUBX_TIME_MSGID, UBX_NMEA_PUBX_TIME_STRID }, + { UBX_RTCM3_CLSID, UBX_RTCM3_TYPE1001_MSGID, UBX_RTCM3_TYPE1001_STRID }, + { UBX_RTCM3_CLSID, UBX_RTCM3_TYPE1002_MSGID, UBX_RTCM3_TYPE1002_STRID }, + { UBX_RTCM3_CLSID, UBX_RTCM3_TYPE1003_MSGID, UBX_RTCM3_TYPE1003_STRID }, + { UBX_RTCM3_CLSID, UBX_RTCM3_TYPE1004_MSGID, UBX_RTCM3_TYPE1004_STRID }, + { UBX_RTCM3_CLSID, UBX_RTCM3_TYPE1005_MSGID, UBX_RTCM3_TYPE1005_STRID }, + { UBX_RTCM3_CLSID, UBX_RTCM3_TYPE1006_MSGID, UBX_RTCM3_TYPE1006_STRID }, + { UBX_RTCM3_CLSID, UBX_RTCM3_TYPE1007_MSGID, UBX_RTCM3_TYPE1007_STRID }, + { UBX_RTCM3_CLSID, UBX_RTCM3_TYPE1009_MSGID, UBX_RTCM3_TYPE1009_STRID }, + { UBX_RTCM3_CLSID, UBX_RTCM3_TYPE1010_MSGID, UBX_RTCM3_TYPE1010_STRID }, + { UBX_RTCM3_CLSID, UBX_RTCM3_TYPE1011_MSGID, UBX_RTCM3_TYPE1011_STRID }, + { UBX_RTCM3_CLSID, UBX_RTCM3_TYPE1012_MSGID, UBX_RTCM3_TYPE1012_STRID }, + { UBX_RTCM3_CLSID, UBX_RTCM3_TYPE1033_MSGID, UBX_RTCM3_TYPE1033_STRID }, + { UBX_RTCM3_CLSID, UBX_RTCM3_TYPE1074_MSGID, UBX_RTCM3_TYPE1074_STRID }, + { UBX_RTCM3_CLSID, UBX_RTCM3_TYPE1075_MSGID, UBX_RTCM3_TYPE1075_STRID }, + { UBX_RTCM3_CLSID, UBX_RTCM3_TYPE1077_MSGID, UBX_RTCM3_TYPE1077_STRID }, + { UBX_RTCM3_CLSID, UBX_RTCM3_TYPE1084_MSGID, UBX_RTCM3_TYPE1084_STRID }, + { UBX_RTCM3_CLSID, UBX_RTCM3_TYPE1085_MSGID, UBX_RTCM3_TYPE1085_STRID }, + { UBX_RTCM3_CLSID, UBX_RTCM3_TYPE1087_MSGID, UBX_RTCM3_TYPE1087_STRID }, + { UBX_RTCM3_CLSID, UBX_RTCM3_TYPE1094_MSGID, UBX_RTCM3_TYPE1094_STRID }, + { UBX_RTCM3_CLSID, UBX_RTCM3_TYPE1095_MSGID, UBX_RTCM3_TYPE1095_STRID }, + { UBX_RTCM3_CLSID, UBX_RTCM3_TYPE1097_MSGID, UBX_RTCM3_TYPE1097_STRID }, + { UBX_RTCM3_CLSID, UBX_RTCM3_TYPE1124_MSGID, UBX_RTCM3_TYPE1124_STRID }, + { UBX_RTCM3_CLSID, UBX_RTCM3_TYPE1125_MSGID, UBX_RTCM3_TYPE1125_STRID }, + { UBX_RTCM3_CLSID, UBX_RTCM3_TYPE1127_MSGID, UBX_RTCM3_TYPE1127_STRID }, + { UBX_RTCM3_CLSID, UBX_RTCM3_TYPE1230_MSGID, UBX_RTCM3_TYPE1230_STRID }, + { UBX_RTCM3_CLSID, UBX_RTCM3_TYPE4072_0_MSGID, UBX_RTCM3_TYPE4072_0_STRID }, + { UBX_RTCM3_CLSID, UBX_RTCM3_TYPE4072_1_MSGID, UBX_RTCM3_TYPE4072_1_STRID }, +}}; +// @fp_codegen_end{FPSDK_COMMON_PARSER_UBX_MSGINFO_CPP} +// clang-format on + +const UbxClassesInfo& UbxGetClassesInfo() +{ + return CLS_INFO; +} + +const UbxMessagesInfo& UbxGetMessagesInfo() +{ + return MSG_INFO; +} + +static bool UbxMessageName(char* name, const std::size_t size, const uint8_t cls_id, const uint8_t msg_id) +{ + // Check arguments + if ((name == NULL) || (size < 1)) { + return false; + } + name[0] = '\0'; + + std::size_t res = 0; + + // First try the message name lookup table + for (auto& info : MSG_INFO) { + if ((info.cls_id_ == cls_id) && (info.msg_id_ == msg_id)) { + res = std::snprintf(name, size, "%s", info.name_); + break; + } + } + + // If that failed, try the class name lookup table + if (res == 0) { + for (auto& info : CLS_INFO) { + if (info.cls_id_ == cls_id) { + res = std::snprintf(name, size, "%s-%02" PRIX8, info.name_, msg_id); + break; + } + } + } + + // If that failed, too, stringify both IDs + if (res == 0) { + res = std::snprintf(name, size, "UBX-%02" PRIX8 "-%02" PRIX8, cls_id, msg_id); + } + + // Did it fit into the string? + return res < size; +} + +bool UbxGetMessageName(char* name, const std::size_t size, const uint8_t* msg, const std::size_t msg_size) +{ + if ((msg == NULL) || (msg_size < UBX_FRAME_SIZE)) { + return false; + } + return UbxMessageName(name, size, UbxClsId(msg), UbxMsgId(msg)); +} + +// --------------------------------------------------------------------------------------------------------------------- + +bool UbxMakeMessage(std::vector& msg, const uint8_t cls_id, const uint8_t msg_id, const uint8_t* payload, + const std::size_t payload_size) +{ + if (((payload == NULL) && (payload_size > 0)) || (payload_size > (MAX_UBX_SIZE - UBX_FRAME_SIZE))) { + return false; + } + + const uint16_t payload_size_u = payload_size; + const std::size_t msg_size = payload_size_u + UBX_FRAME_SIZE; + msg.resize(msg_size); + msg[0] = UBX_SYNC_1; + msg[1] = UBX_SYNC_2; + msg[2] = cls_id; + msg[3] = msg_id; + msg[4] = (payload_size_u & 0xff); + msg[5] = (payload_size_u >> 8); + if ((payload != NULL) && (payload_size_u > 0)) { + std::memcpy(&msg[UBX_HEAD_SIZE], payload, payload_size_u); + } + const uint16_t ck = crc::ChecksumUbx(&msg[2], msg_size - 2 - 2); + msg[msg_size - 2] = (ck & 0xff); + msg[msg_size - 1] = (ck >> 8); + return true; +} + +bool UbxMakeMessage( + std::vector& msg, const uint8_t cls_id, const uint8_t msg_id, const std::vector& payload) +{ + return UbxMakeMessage(msg, cls_id, msg_id, payload.data(), payload.size()); +} + +// --------------------------------------------------------------------------------------------------------------------- + +std::size_t UbxRxmSfrbxInfo(char* info, const std::size_t size, const uint8_t* msg, const std::size_t msg_size) +{ + if ((UBX_RXM_SFRBX_VERSION_GET(msg) != UBX_RXM_SFRBX_V2_VERSION) || (msg_size < UBX_RXM_SFRBX_V2_MIN_SIZE)) { + return 0; + } + + // Meta information + UBX_RXM_SFRBX_V2_GROUP0 head; + std::memcpy(&head, &msg[UBX_HEAD_SIZE], sizeof(head)); + + // Raw sub_frame words + uint32_t dwrd[30]; + std::size_t n_dwrd = (msg_size - UBX_FRAME_SIZE - (sizeof(head)) / sizeof(*dwrd)); + if (n_dwrd == 0) { + return std::snprintf(info, size, "empty"); + } + std::memcpy( + &dwrd[0], &msg[UBX_HEAD_SIZE + sizeof(head)], std::min(sizeof(dwrd) / sizeof(*dwrd), n_dwrd) * sizeof(*dwrd)); + + // Sources: + // - ZED-F9P Integration Manual, 3.13.1 Broadcast navigation data + // - IS-GPS-200M + // - Galileo OS SIS ICD + // - Navipedia + + // GPS L1 C/A LNAV message + if ((head.gnssId == UBX_GNSSID_GPS) && (head.sigId == UBX_SIGID_GPS_L1CA) && (n_dwrd == 10)) { + // const uint16_t towCount = (info.dwrd[1] & 0x3fffe000) >> 13; + const uint8_t sub_frame = (dwrd[1] & 0x00000700) >> 8; + if ((1 <= sub_frame) && (sub_frame <= 3)) { + return std::snprintf(info, size, "GPS LNAV eph %u/3", sub_frame); + } else { + const uint8_t data_id = (dwrd[2] & 0x30000000) >> 28; + if (data_id == 1) { + const uint8_t sv_id = (dwrd[2] & 0x0fc00000) >> 22; // 20.3.3.5.1, 20.3.3.5.1.1 (Table 20-V) + // sub frame 5 pages 1-24, sub_frame 4 pages 2-5 and 7-10 + if ((1 <= sv_id) && (sv_id <= 32)) { + return std::snprintf(info, size, "GPS LNAV alm %0u", sv_id); + } + // sub frame 5, page 25 + else if (sv_id == 51) { + return std::snprintf(info, size, "GPS LNAV toa, health"); // health 1-24, ALM reference time + } + // sub frame 4, page 13 + else if (sv_id == 52) { + return std::snprintf(info, size, "GPS LNAV NCMT"); + } + // sub frame 4, page 17 + else if (sv_id == 55) { + return std::snprintf(info, size, "GPS LNAV special"); + } + // sub frame 4, page 18 + else if (sv_id == 56) { + return std::snprintf(info, size, "GPS LNAV iono, UTC"); + } + // sub frame 4, page 25 + else if (sv_id == 63) { + return std::snprintf(info, size, "GPS LNAV AS, health"); // anti-spoofing flags, health 25-32 + } + // reserved + else { + return std::snprintf(info, size, "GPS LNAV reserved"); + } + } + } + return std::snprintf(info, size, "bad GPS sf?"); // Hmm.. should we check the parity first? + } + + // GPS CNAV message (12 seconds, 300 bits) + else if ((head.gnssId == UBX_GNSSID_GPS) && + ((head.sigId == UBX_SIGID_GPS_L2CL) || (head.sigId == UBX_SIGID_GPS_L2CM)) && (n_dwrd == 10)) { + const uint8_t msg_type_id = (dwrd[0] & 0x0003f000) >> 12; + const char* const msg_type_descs[] = { + // clang-format off + NULL, NULL, NULL, NULL, NULL, + NULL, NULL, NULL, NULL, NULL, + /* 10 */ "eph 1", /* 11 */ "eph 2", /* 12 */ "red alm", /* 13 */ "clock diff", /* 14 */ "eph diff", + /* 15 */ "text", NULL, NULL, NULL, NULL, + NULL, NULL, NULL, NULL, NULL, + NULL, NULL, NULL, NULL, NULL, + /* 30 */ "iono, clk, tgd", /* 31 */ "clock, red. alm", /* 32 */ "clock, EOP", /* 33 */ "clock, UTC", /* 34 */ "clock, diff", + /* 35 */ "clock, GGTO", /* 36 */ "clock, text", /* 37 */ "clock, mid alm", NULL, NULL, + /* 40 */ "integrity", + }; // clang-format on + return std::snprintf(info, size, "GPS CNAV msg %u %s", msg_type_id, + (msg_type_id < (sizeof(msg_type_descs) / sizeof(*msg_type_descs))) && msg_type_descs[msg_type_id] + ? msg_type_descs[msg_type_id] + : ""); + } + + // GLONASS strings + else if (head.gnssId == UBX_GNSSID_GLO) { + // clang-format off + const uint8_t string = (dwrd[0] & 0x78000000) >> 27; + const uint16_t super_frame = (dwrd[3] & 0xffff0000) >> 16; + const uint16_t frame = (dwrd[3] & 0x0000000f); + // clang-format on + return std::snprintf(info, size, "GLO sup %u fr %u str %u", super_frame, frame, string); + } + + // Galileo I/NAV + else if ((head.gnssId == UBX_GNSSID_GAL) && + ((head.sigId == UBX_SIGID_GAL_E1B) || (head.sigId == UBX_SIGID_GAL_E5BI))) { + // FIXME: to check.. the u-blox manual is weird here + // clang-format off + const char even_odd_1 = (dwrd[0] & 0x80000000) == 0x80000000 ? 'o' : 'e'; // even (0) or odd (1) + const char page_type_1 = (dwrd[0] & 0x40000000) == 0x40000000 ? 'a' : 'n'; // nominal (0) or alert (1) + const uint8_t word_type_1 = (dwrd[0] & 0x3f000000) >> 24; + const char even_odd_2 = (dwrd[4] & 0x80000000) == 0x80000000 ? 'o' : 'e'; // even (0) or odd (1) + const char page_type_2 = (dwrd[4] & 0x40000000) == 0x40000000 ? 'a' : 'n'; // nominal (0) or alert (1) + const uint8_t word_type_2 = (dwrd[4] & 0x3f000000) >> 24; + // clang-format on + return std::snprintf(info, size, "GAL I/NAV %c %c %u, %c %c %u", page_type_1, even_odd_1, word_type_1, + page_type_2, even_odd_2, word_type_2); + } + + // unknown + return std::snprintf(info, size, "unknown (n=%d, 0x%08x, 0x%08x, ...)", (int)n_dwrd, dwrd[0], dwrd[1]); +} + +// --------------------------------------------------------------------------------------------------------------------- + +std::size_t UbxMonVerToVerStr(char* str, const std::size_t size, const uint8_t* msg, const std::size_t msg_size) +{ + if ((msg == NULL) || (str == NULL) || (size < 2) || (UbxClsId(msg) != UBX_MON_CLSID) || + (UbxMsgId(msg) != UBX_MON_VER_MSGID) || (msg_size < (UBX_FRAME_SIZE + sizeof(UBX_MON_VER_V0_GROUP0)))) { + return false; + } + + // swVersion: EXT CORE 1.00 (61ce84) + // hwVersion: 00190000 + // extension: ROM BASE 0xDD3FE36C + // extension: FWVER=HPG 1.00 + // extension: PROTVER=27.00 + // extension: MOD=ZED-F9P + // extension: GPS;GLO;GAL;BDS + // extension: QZSS + + UBX_MON_VER_V0_GROUP0 gr0; + std::size_t offs = UBX_HEAD_SIZE; + std::memcpy(&gr0, &msg[offs], sizeof(gr0)); + gr0.swVersion[sizeof(gr0.swVersion) - 1] = '\0'; + + char verStr[sizeof(gr0.swVersion)]; + verStr[0] = '\0'; + char modStr[sizeof(gr0.swVersion)]; + modStr[0] = '\0'; + + offs += sizeof(gr0); + UBX_MON_VER_V0_GROUP1 gr1; + while (offs <= (msg_size - 2 - sizeof(gr1))) { + std::memcpy(&gr1, &msg[offs], sizeof(gr1)); + if ((verStr[0] == '\0') && (strncmp("FWVER=", gr1.extension, 6) == 0)) { + gr1.extension[sizeof(gr1.extension) - 1] = '\0'; + strcat(verStr, &gr1.extension[6]); + } else if ((modStr[0] == '\0') && (strncmp("MOD=", gr1.extension, 4) == 0)) { + gr1.extension[sizeof(gr1.extension) - 1] = '\0'; + strcat(modStr, &gr1.extension[4]); + } + offs += sizeof(gr1); + if ((verStr[0] != '\0') && (modStr[0] != '\0')) { + break; + } + } + if (verStr[0] == '\0') { + strcat(verStr, gr0.swVersion); + } + + std::size_t len = 0; + if (modStr[0] != '\0') { + len = std::snprintf(str, size, "%s (%s)", verStr, modStr); + } else { + len = std::snprintf(str, size, "%s", verStr); + } + return len; +} + +// --------------------------------------------------------------------------------------------------------------------- + +#define UbxSvStr(gnssId, svId) fpsdk::common::gnss::SatStr(fpsdk::common::gnss::UbxGnssIdSvIdToSat(gnssId, svId)) + +static std::size_t StrUbxNav( + char* info, const std::size_t size, const uint8_t* msg, const std::size_t msg_size, const std::size_t iTowOffs) +{ + if (msg_size < (UBX_FRAME_SIZE + iTowOffs + sizeof(uint32_t))) { + return 0; + } + uint32_t iTOW; + std::memcpy(&iTOW, &msg[UBX_HEAD_SIZE + iTowOffs], sizeof(iTOW)); + const std::size_t n = std::snprintf(info, size, "%010.3f", (double)iTOW * 1e-3); + return n; +} + +static std::size_t StrUbxNavPvt(char* info, const std::size_t size, const uint8_t* msg, const std::size_t msg_size) +{ + if (msg_size != UBX_NAV_PVT_V1_SIZE) { + return 0; + } + UBX_NAV_PVT_V1_GROUP0 pvt; + std::memcpy(&pvt, &msg[UBX_HEAD_SIZE], sizeof(pvt)); + int sec = pvt.sec; + int msec = (pvt.nano / 1000 + 500) / 1000; + if (msec < 0) { + sec -= 1; + msec = 1000 + msec; + } + const std::size_t carrSoln = UBX_NAV_PVT_V1_FLAGS_CARRSOLN_GET(pvt.flags); + constexpr std::array fixTypes = { { "nofix", "dr", "2D", "3D", "3D+DR", "time" } }; + const std::size_t n = std::snprintf(info, size, + "%010.3f" + " %04u-%02u-%02u (%c)" + " %02u:%02u:%02d.%03d (%c)" + " %s (%s, %s)" + " %2d %4.2f" + " %+11.7f %+12.7f (%5.1f) %+6.0f (%5.1f)", + (double)pvt.iTOW * 1e-3, pvt.year, pvt.month, pvt.day, + UBX_NAV_PVT_V1_VALID_VALIDDATE(pvt.valid) ? (UBX_NAV_PVT_V1_FLAGS2_CONFDATE(pvt.flags2) ? 'Y' : 'y') : 'n', + pvt.hour, pvt.min, sec, msec, + UBX_NAV_PVT_V1_VALID_VALIDTIME(pvt.valid) ? (UBX_NAV_PVT_V1_FLAGS2_CONFTIME(pvt.flags2) ? 'Y' : 'y') : 'n', + pvt.fixType < fixTypes.size() ? fixTypes[pvt.fixType] : "?", + UBX_NAV_PVT_V1_FLAGS_GNSSFIXOK(pvt.flags) ? "OK" : "masked", + carrSoln == UBX_NAV_PVT_V1_FLAGS_CARRSOLN_NO + ? "none" + : (carrSoln == UBX_NAV_PVT_V1_FLAGS_CARRSOLN_FLOAT + ? "float" + : (carrSoln == UBX_NAV_PVT_V1_FLAGS_CARRSOLN_FIXED ? "fixed" : "rtk?")), + pvt.numSV, (double)pvt.pDOP * UBX_NAV_PVT_V1_PDOP_SCALE, (double)pvt.lat * UBX_NAV_PVT_V1_LAT_SCALE, + (double)pvt.lon * UBX_NAV_PVT_V1_LON_SCALE, (double)pvt.hAcc * UBX_NAV_PVT_V1_HACC_SCALE, + (double)pvt.height * UBX_NAV_PVT_V1_HEIGHT_SCALE, (double)pvt.vAcc * UBX_NAV_PVT_V1_VACC_SCALE); + return n; +} + +static std::size_t StrUbxNavPosecef(char* info, const std::size_t size, const uint8_t* msg, const std::size_t msg_size) +{ + if (msg_size != UBX_NAV_POSECEF_V0_SIZE) { + return 0; + } + UBX_NAV_POSECEF_V0_GROUP0 pos; + std::memcpy(&pos, &msg[UBX_HEAD_SIZE], sizeof(pos)); + const std::size_t n = std::snprintf(info, size, "%010.3f %.2f %.2f %.2f %.2f", (double)pos.iTOW * 1e-3, + (double)pos.ecefX * UBX_NAV_POSECEF_V0_ECEF_XYZ_SCALE, (double)pos.ecefY * UBX_NAV_POSECEF_V0_ECEF_XYZ_SCALE, + (double)pos.ecefZ * UBX_NAV_POSECEF_V0_ECEF_XYZ_SCALE, (double)pos.pAcc * UBX_NAV_POSECEF_V0_PACC_SCALE); + return n; +} + +static std::size_t StrUbxNavHpposecef( + char* info, const std::size_t size, const uint8_t* msg, const std::size_t msg_size) +{ + if ((msg_size != UBX_NAV_HPPOSECEF_V0_SIZE) || + (UBX_NAV_HPPOSECEF_VERSION_GET(msg) != UBX_NAV_HPPOSECEF_V0_VERSION)) { + return 0; + } + UBX_NAV_HPPOSECEF_V0_GROUP0 pos; + std::memcpy(&pos, &msg[UBX_HEAD_SIZE], sizeof(pos)); + if (!UBX_NAV_HPPOSECEF_V0_FLAGS_INVALIDECEF(pos.flags)) { + return std::snprintf(info, size, "%010.3f %.3f %.3f %.3f %.3f", (double)pos.iTOW * 1e-3, + ((double)pos.ecefX * UBX_NAV_HPPOSECEF_V0_ECEF_XYZ_SCALE) + + ((double)pos.ecefXHp * UBX_NAV_HPPOSECEF_V0_ECEF_XYZ_HP_SCALE), + ((double)pos.ecefY * UBX_NAV_HPPOSECEF_V0_ECEF_XYZ_SCALE) + + ((double)pos.ecefYHp * UBX_NAV_HPPOSECEF_V0_ECEF_XYZ_HP_SCALE), + ((double)pos.ecefZ * UBX_NAV_HPPOSECEF_V0_ECEF_XYZ_SCALE) + + ((double)pos.ecefZHp * UBX_NAV_HPPOSECEF_V0_ECEF_XYZ_HP_SCALE), + (double)pos.pAcc * UBX_NAV_HPPOSECEF_V0_PACC_SCALE); + } else { + return std::snprintf(info, size, "%010.3f invalid", (double)pos.iTOW * 1e-3); + } +} + +static std::size_t StrUbxNavRelposned( + char* info, const std::size_t size, const uint8_t* msg, const std::size_t msg_size) +{ + if ((msg_size != UBX_NAV_RELPOSNED_V1_SIZE) || + (UBX_NAV_RELPOSNED_VERSION_GET(msg) != UBX_NAV_RELPOSNED_V1_VERSION)) { + return 0; + } + UBX_NAV_RELPOSNED_V1_GROUP0 rel; + std::memcpy(&rel, &msg[UBX_HEAD_SIZE], sizeof(rel)); + const std::size_t carrSoln = UBX_NAV_RELPOSNED_V1_FLAGS_CARRSOLN_GET(rel.flags); + return std::snprintf(info, size, + "%010.3f N %.3f E %.3f D %.3f L %.3f (%.3f) H %.1f (%.1f) %s %s %s pos:%c head:%c moving:%c posMiss:%c " + "obsMiss:%c norm:%c", + (double)rel.iTOW * 1e-3, + ((double)rel.relPosN * UBX_NAV_RELPOSNED_V1_RELPOSN_E_D_SCALE) + + ((double)rel.relPosHPN * UBX_NAV_RELPOSNED_V1_RELPOSHPN_E_D_SCALE), + ((double)rel.relPosE * UBX_NAV_RELPOSNED_V1_RELPOSN_E_D_SCALE) + + ((double)rel.relPosHPE * UBX_NAV_RELPOSNED_V1_RELPOSHPN_E_D_SCALE), + ((double)rel.relPosD * UBX_NAV_RELPOSNED_V1_RELPOSN_E_D_SCALE) + + ((double)rel.relPosHPD * UBX_NAV_RELPOSNED_V1_RELPOSHPN_E_D_SCALE), + ((double)rel.relPosLength * UBX_NAV_RELPOSNED_V1_RELPOSLENGTH_SCALE) + + ((double)rel.relPosHPLength * UBX_NAV_RELPOSNED_V1_RELPOSHPLENGTH_SCALE), + ((double)rel.accLength * UBX_NAV_RELPOSNED_V1_ACCLENGTH_SCALE), + ((double)rel.relPosHeading * UBX_NAV_RELPOSNED_V1_RELPOSHEADING_SCALE), + ((double)rel.accHeading * UBX_NAV_RELPOSNED_V1_ACCHEADING_SCALE), + UBX_NAV_RELPOSNED_V1_FLAGS_GNSSFIXOK(rel.flags) ? "OK" : "masked", + UBX_NAV_RELPOSNED_V1_FLAGS_DIFFSOLN(rel.flags) ? "diff" : "(diff)", + carrSoln == 0 ? "none" : (carrSoln == 1 ? "float" : (carrSoln == 2 ? "fixed" : "rtk?")), + UBX_NAV_RELPOSNED_V1_FLAGS_RELPOSVALID(rel.flags) ? 'Y' : 'N', + UBX_NAV_RELPOSNED_V1_FLAGS_RELPOSHEADINGVALID(rel.flags) ? 'Y' : 'N', + UBX_NAV_RELPOSNED_V1_FLAGS_ISMOVING(rel.flags) ? 'Y' : 'N', + UBX_NAV_RELPOSNED_V1_FLAGS_REFPOSMISS(rel.flags) ? 'Y' : 'N', + UBX_NAV_RELPOSNED_V1_FLAGS_REFOBSMISS(rel.flags) ? 'Y' : 'N', + UBX_NAV_RELPOSNED_V1_FLAGS_RELPOSNORMALIZED(rel.flags) ? 'Y' : 'N'); +} + +static std::size_t StrUbxNavStatus(char* info, const std::size_t size, const uint8_t* msg, const std::size_t msg_size) +{ + if (msg_size != UBX_NAV_STATUS_V0_SIZE) { + return 0; + } + UBX_NAV_STATUS_V0_GROUP0 sta; + std::memcpy(&sta, &msg[UBX_HEAD_SIZE], sizeof(sta)); + return std::snprintf(info, size, "%010.3f ttff=%.3f sss=%.3f", (double)sta.iTow * 1e-3, (double)sta.ttff * 1e-3, + (double)sta.msss * 1e-3); +} + +static std::size_t StrUbxNavTimegps(char* info, const std::size_t size, const uint8_t* msg, const std::size_t msg_size) +{ + if (msg_size != UBX_NAV_TIMEGPS_V0_SIZE) { + return 0; + } + UBX_NAV_TIMEGPS_V0_GROUP0 gps; + std::memcpy(&gps, &msg[UBX_HEAD_SIZE], sizeof(gps)); + return std::snprintf(info, size, "%010.3f %04u %c %019.9f %c %e %d %c", + (double)gps.iTow * UBX_NAV_TIMEGPS_V0_ITOW_SCALE, gps.week, + UBX_NAV_TIMEGPS_V0_VALID_WEEKVALID(gps.valid) ? 'Y' : 'N', + ((double)gps.iTow * UBX_NAV_TIMEGPS_V0_ITOW_SCALE) + ((double)gps.fTOW * UBX_NAV_TIMEGPS_V0_FTOW_SCALE), + UBX_NAV_TIMEGPS_V0_VALID_TOWVALID(gps.valid) ? 'Y' : 'N', (double)gps.tAcc * UBX_NAV_TIMEGPS_V0_TACC_SCALE, + gps.leapS, UBX_NAV_TIMEGPS_V0_VALID_LEAPSVALID(gps.valid) ? 'Y' : 'N'); +} + +static std::size_t StrUbxNavTimegal(char* info, const std::size_t size, const uint8_t* msg, const std::size_t msg_size) +{ + if (msg_size != UBX_NAV_TIMEGAL_V0_SIZE) { + return 0; + } + UBX_NAV_TIMEGAL_V0_GROUP0 gal; + std::memcpy(&gal, &msg[UBX_HEAD_SIZE], sizeof(gal)); + return std::snprintf(info, size, "%010.3f %04u %c %019.9f %c %e %d %c", + (double)gal.iTow * UBX_NAV_TIMEGAL_V0_ITOW_SCALE, gal.galWno, + UBX_NAV_TIMEGAL_V0_VALID_GALWNOVALID(gal.valid) ? 'Y' : 'N', + (double)gal.galTow + ((double)gal.fGalTow * UBX_NAV_TIMEGAL_V0_FGALTOW_SCALE), + UBX_NAV_TIMEGAL_V0_VALID_GALTOWVALID(gal.valid) ? 'Y' : 'N', (double)gal.tAcc * UBX_NAV_TIMEGAL_V0_TACC_SCALE, + gal.leapS, UBX_NAV_TIMEGAL_V0_VALID_LEAPSVALID(gal.valid) ? 'Y' : 'N'); +} + +static std::size_t StrUbxNavTimebds(char* info, const std::size_t size, const uint8_t* msg, const std::size_t msg_size) +{ + if (msg_size != UBX_NAV_TIMEBDS_V0_SIZE) { + return 0; + } + UBX_NAV_TIMEBDS_V0_GROUP0 bds; + std::memcpy(&bds, &msg[UBX_HEAD_SIZE], sizeof(bds)); + return std::snprintf(info, size, "%010.3f %04u %c %019.9f %c %e %d %c", + (double)bds.iTow * UBX_NAV_TIMEBDS_V0_ITOW_SCALE, bds.week, + UBX_NAV_TIMEBDS_V0_VALID_WEEKVALID(bds.valid) ? 'Y' : 'N', + (double)bds.SOW + ((double)bds.fSOW * UBX_NAV_TIMEBDS_V0_FSOW_SCALE), + UBX_NAV_TIMEBDS_V0_VALID_SOWVALID(bds.valid) ? 'Y' : 'N', (double)bds.tAcc * UBX_NAV_TIMEGAL_V0_TACC_SCALE, + bds.leapS, UBX_NAV_TIMEBDS_V0_VALID_LEAPSVALID(bds.valid) ? 'Y' : 'N'); +} + +static std::size_t StrUbxNavTimeglo(char* info, const std::size_t size, const uint8_t* msg, const std::size_t msg_size) +{ + if (msg_size != UBX_NAV_TIMEGLO_V0_SIZE) { + return 0; + } + UBX_NAV_TIMEGLO_V0_GROUP0 glo; + std::memcpy(&glo, &msg[UBX_HEAD_SIZE], sizeof(glo)); + return std::snprintf(info, size, "%010.3f %03u %04u %c %015.9f %c %e", + (double)glo.iTow * UBX_NAV_TIMEGLO_V0_ITOW_SCALE, glo.N4, glo.Nt, + UBX_NAV_TIMEGLO_V0_VALID_DATEVALID(glo.valid) ? 'Y' : 'N', + (double)glo.TOD + ((double)glo.fTOD * UBX_NAV_TIMEGLO_V0_FTOD_SCALE), + UBX_NAV_TIMEGLO_V0_VALID_TODVALID(glo.valid) ? 'Y' : 'N', (double)glo.tAcc * UBX_NAV_TIMEGAL_V0_TACC_SCALE); +} + +static std::size_t StrUbxNavTimeutc(char* info, const std::size_t size, const uint8_t* msg, const std::size_t msg_size) +{ + if (msg_size != UBX_NAV_TIMEUTC_V0_SIZE) { + return 0; + } + UBX_NAV_TIMEUTC_V0_GROUP0 utc; + std::memcpy(&utc, &msg[UBX_HEAD_SIZE], sizeof(utc)); + const uint8_t utcStandard = UBX_NAV_TIMEUTC_V0_VALID_UTCSTANDARD_GET(utc.valid); + constexpr std::array utcStandardStr = { { "NA", "CRL", "NIST", "USNO", "BIPM", "EU", "SU", "NTSC", + "NPLI" } }; + return std::snprintf(info, size, "%010.3f %c %04u-%02u-%02u %c %02u:%02u:%02u.%03u %c %s", + (double)utc.iTow * UBX_NAV_TIMEUTC_V0_ITOW_SCALE, UBX_NAV_TIMEUTC_V0_VALID_VALIDWKN(utc.valid) ? 'Y' : 'N', + utc.year, utc.month, utc.day, UBX_NAV_TIMEUTC_V0_VALID_VALIDTOW(utc.valid) ? 'Y' : 'N', utc.hour, utc.min, + utc.sec, (int)(utc.nano * UBX_NAV_TIMEUTC_V0_NANO_SCALE) / 1000000, + UBX_NAV_TIMEUTC_V0_VALID_VALIDUTC(utc.valid) ? 'Y' : 'N', + utcStandard < utcStandardStr.size() ? utcStandardStr[utcStandard] : "?"); +} + +static std::size_t StrUbxNavSig(char* info, const std::size_t size, const uint8_t* msg, const std::size_t msg_size) +{ + if ((msg_size < UBX_NAV_SIG_V0_MIN_SIZE) || (UBX_NAV_SIG_VERSION_GET(msg) != UBX_NAV_SIG_V0_VERSION)) { + return 0; + } + UBX_NAV_SIG_V0_GROUP0 head; + std::memcpy(&head, &msg[UBX_HEAD_SIZE], sizeof(head)); + return std::snprintf(info, size, "%010.3f %d", (double)head.iTOW * 1e-3, head.numSigs); +} + +static std::size_t StrUbxNavSat(char* info, const std::size_t size, const uint8_t* msg, const std::size_t msg_size) +{ + if ((msg_size < UBX_NAV_SAT_V1_MIN_SIZE) || (UBX_NAV_SAT_VERSION_GET(msg) != UBX_NAV_SAT_V1_VERSION)) { + return 0; + } + UBX_NAV_SAT_V1_GROUP0 head; + std::memcpy(&head, &msg[UBX_HEAD_SIZE], sizeof(head)); + return std::snprintf(info, size, "%010.3f %d", (double)head.iTOW * 1e-3, head.numSvs); +} + +static std::size_t StrUbxInf(char* info, const std::size_t size, const uint8_t* msg, const std::size_t msg_size) +{ + if (msg_size < UBX_FRAME_SIZE) { + return 0; + } + const std::size_t infLen = msg_size - UBX_FRAME_SIZE; + const std::size_t maxLen = size - 1; + const std::size_t copyLen = std::min(infLen, maxLen); + std::memcpy(info, &msg[UBX_HEAD_SIZE], copyLen); + info[copyLen] = '\0'; + for (std::size_t ix = 0; ix < copyLen; ix++) { + if (std::isprint(info[ix]) == 0) { + info[ix] = '.'; + } + } + return copyLen; +} + +static std::size_t StrUbxMonVer(char* info, const std::size_t size, const uint8_t* msg, const std::size_t msg_size) +{ + return UbxMonVerToVerStr(info, size, msg, msg_size); +} + +static std::size_t StrUbxMonTemp(char* info, const std::size_t size, const uint8_t* msg, const std::size_t msg_size) +{ + if ((UBX_MON_TEMP_VERSION_GET(msg) != UBX_MON_TEMP_V0_VERSION) || (msg_size != UBX_MON_TEMP_V0_SIZE)) { + return 0; + } + UBX_MON_TEMP_V0_GROUP0 temp; + std::memcpy(&temp, &msg[UBX_HEAD_SIZE], sizeof(temp)); + return std::snprintf(info, size, "%d C, %d", temp.temperature, temp.unknown); +} + +static std::size_t StrUbxRxmSfrbx(char* info, const std::size_t size, const uint8_t* msg, const std::size_t msg_size) +{ + if ((UBX_RXM_SFRBX_VERSION_GET(msg) != UBX_RXM_SFRBX_V2_VERSION) || (msg_size < UBX_RXM_SFRBX_V2_MIN_SIZE)) { + return 0; + } + + if (size < 10) { + return 0; + } + const int nDwrd = (msg_size - UBX_FRAME_SIZE - sizeof(UBX_RXM_SFRBX_V2_GROUP0)) / sizeof(uint32_t); + const std::size_t len = + std::snprintf(info, size, "%s %d: ", UbxSvStr(msg[UBX_HEAD_SIZE], msg[UBX_HEAD_SIZE + 1]), nDwrd); + return len + UbxRxmSfrbxInfo(&info[len], size - len, msg, msg_size); +} + +static std::size_t StrUbxCfgValset(char* info, const std::size_t size, const uint8_t* msg, const std::size_t msg_size) +{ + using namespace fpsdk::common::math; + if (msg_size < sizeof(UBX_CFG_VALSET_V1_GROUP0)) { + return 0; + } + UBX_CFG_VALSET_V1_GROUP0 /* (~= UBX_CFG_VALGET_V0_GROUP0) */ head; + std::memcpy(&head, &msg[UBX_HEAD_SIZE], sizeof(head)); + const int dataSize = msg_size - UBX_FRAME_SIZE - sizeof(head); + char layers[100]; + layers[0] = '\0'; + layers[1] = '\0'; + std::size_t len = 0; + if (CheckBitsAll(head.layers, Bit(UBX_CFG_VALSET_V1_LAYERS_RAM))) { + len += std::snprintf(&layers[len], sizeof(layers) - len, ",RAM"); + } + if (CheckBitsAll(head.layers, Bit(UBX_CFG_VALSET_V1_LAYERS_BBR))) { + len += std::snprintf(&layers[len], sizeof(layers) - len, ",BBR"); + } + if (CheckBitsAll(head.layers, Bit(UBX_CFG_VALSET_V1_LAYERS_FLASH))) { + len += std::snprintf(&layers[len], sizeof(layers) - len, ",Flash"); + } + switch (head.version) { + case UBX_CFG_VALSET_V0_VERSION: { + return std::snprintf(info, size, "set %d bytes, layers %s", dataSize, &layers[1]); + break; + } + case UBX_CFG_VALSET_V1_VERSION: { + const char* transaction = "?"; + switch (head.transaction) { + case UBX_CFG_VALSET_V1_TRANSACTION_NONE: + transaction = "none"; + break; + case UBX_CFG_VALSET_V1_TRANSACTION_BEGIN: + transaction = "begin"; + break; + case UBX_CFG_VALSET_V1_TRANSACTION_CONTINUE: + transaction = "continue"; + break; + case UBX_CFG_VALSET_V1_TRANSACTION_END: + transaction = "end"; + break; + } + return std::snprintf( + info, size, "set %d bytes, layers %s, transaction %s", dataSize, &layers[1], transaction); + break; + } + } + return 0; +} + +static const char* _valgetLayerName(const uint8_t layer) +{ + switch (layer) { + case UBX_CFG_VALGET_V1_LAYER_RAM: + return "RAM"; + case UBX_CFG_VALGET_V1_LAYER_BBR: + return "BBR"; + case UBX_CFG_VALGET_V1_LAYER_FLASH: + return "Flash"; + case UBX_CFG_VALGET_V1_LAYER_DEFAULT: + return "Default"; + } + return "?"; +} + +static std::size_t StrUbxCfgValget(char* info, const std::size_t size, const uint8_t* msg, const std::size_t msg_size) +{ + if (msg_size < sizeof(UBX_CFG_VALGET_V0_GROUP0)) { + return 0; + } + UBX_CFG_VALGET_V0_GROUP0 head; + std::memcpy(&head, &msg[UBX_HEAD_SIZE], sizeof(head)); + switch (head.version) { + case UBX_CFG_VALGET_V0_VERSION: { + const int numKeys = (msg_size - UBX_FRAME_SIZE - sizeof(head)) / sizeof(uint32_t); + return std::snprintf(info, size, "poll %d items, layer %s, position %u", numKeys, + _valgetLayerName(head.layer), head.position); + break; + } + case UBX_CFG_VALGET_V1_VERSION: { + const int dataSize = size - UBX_FRAME_SIZE - sizeof(head); + return std::snprintf(info, size, "response %d bytes, layer %s, position %u", dataSize, + _valgetLayerName(head.layer), head.position); + break; + } + } + return 0; +} + +static std::size_t StrUbxAckAck( + char* info, const std::size_t size, const uint8_t* msg, const std::size_t msg_size, const bool ack) +{ + if (msg_size < sizeof(UBX_ACK_ACK_V0_GROUP0)) { + return 0; + } + UBX_ACK_ACK_V0_GROUP0 /* (= UBX_ACK_NAK_V0_GROUP0_t) */ acknak; + std::memcpy(&acknak, &msg[UBX_HEAD_SIZE], sizeof(acknak)); + char tmp[100]; + UbxMessageName(tmp, sizeof(tmp), acknak.clsId, acknak.msgId); + return std::snprintf(info, size, "%s %s", ack ? "acknowledgement" : "negative-acknowledgement", tmp); +} + +static std::size_t StrUbxTimTm2(char* info, const std::size_t size, const uint8_t* msg, const std::size_t msg_size) +{ + if (msg_size != UBX_TIM_TM2_V0_SIZE) { + return 0; + } + UBX_TIM_TM2_V0_GROUP0 tm; + std::memcpy(&tm, &msg[UBX_HEAD_SIZE], sizeof(tm)); + + const uint8_t timeBase = UBX_TIM_TM2_V0_FLAGS_TIMEBASE_GET(tm.flags); + constexpr std::array timeBaseStr = { { "RX", "GNSS", "UTC" } }; + const double towR = + ((double)tm.towMsR * UBX_TIM_TM2_V0_TOW_SCALE) + ((double)tm.towSubMsR * UBX_TIM_TM2_V0_SUBMS_SCALE); + const double towF = + ((double)tm.towMsF * UBX_TIM_TM2_V0_TOW_SCALE) + ((double)tm.towSubMsF * UBX_TIM_TM2_V0_SUBMS_SCALE); + + return std::snprintf(info, size, "%04u:%013.6f %04u:%013.6f INT%u %c %c %s %s %s %s %s %u %.6g", tm.wnR, towR, + tm.wnF, towF, tm.ch, UBX_TIM_TM2_V0_FLAGS_NEWRISINGEDGE(tm.flags) ? 'R' : '-', + UBX_TIM_TM2_V0_FLAGS_NEWFALLINGEDGE(tm.flags) ? 'F' : '-', + UBX_TIM_TM2_V0_FLAGS_MODE_GET(tm.flags) == UBX_TIM_TM2_V0_FLAGS_MODE_SINGLE ? "single" : "running", + UBX_TIM_TM2_V0_FLAGS_RUN_GET(tm.flags) == UBX_TIM_TM2_V0_FLAGS_RUN_ARMED ? "armed" : "stopped", + timeBase < timeBaseStr.size() ? timeBaseStr[timeBase] : "?", + UBX_TIM_TM2_V0_FLAGS_UTCACAVAIL(tm.flags) ? "UTC" : "n/a", + UBX_TIM_TM2_V0_FLAGS_TIMEVALID(tm.flags) ? "valid" : "invalid", tm.count, + (double)tm.accEst * UBX_TIM_TM2_V0_ACCEST_SCALE); +} +static std::size_t StrUbxTimTp(char* info, const std::size_t size, const uint8_t* msg, const std::size_t msg_size) +{ + // clang-format off + // message 11, dt 63, size 36, UBX UBX-TIM-TM2 2253:061563.388047 2253:061563.588086 INT0 - F running armed GNSS n/a valid 46887 1.3e-08 + // message 43, dt 558, size 36, UBX UBX-TIM-TM2 2253:061564.387529 2253:061563.588086 INT0 R - running armed GNSS n/a valid 46888 1.3e-08 + // message 67, dt 64, size 36, UBX UBX-TIM-TM2 2253:061564.387529 2253:061564.588060 INT0 - F running armed GNSS n/a valid 46888 1.3e-08 + // message 91, dt 556, size 36, UBX UBX-TIM-TM2 2253:061565.387023 2253:061564.588060 INT0 R - running armed GNSS n/a valid 46889 1.3e-08 + // message 115, dt 67, size 36, UBX UBX-TIM-TM2 2253:061565.387023 2253:061565.587034 INT0 - F running armed GNSS n/a valid 46889 1.3e-08 + // message 154, dt 558, size 36, UBX UBX-TIM-TM2 2253:061566.386456 2253:061565.587034 INT0 R - running armed GNSS n/a valid 46890 1.3e-08 + // message 173, dt 66, size 36, UBX UBX-TIM-TM2 2253:061566.386456 2253:061566.587008 INT0 - F running armed GNSS n/a valid 46890 1.3e-08 + // message 202, dt 569, size 36, UBX UBX-TIM-TM2 2253:061567.385907 2253:061566.587008 INT0 R - running armed GNSS n/a valid 46891 1.3e-08 + // message 226, dt 59, size 36, UBX UBX-TIM-TM2 2253:061567.385907 2253:061567.585982 INT0 - F running armed GNSS n/a valid 46891 1.3e-08 + // message 263, dt 566, size 36, UBX UBX-TIM-TM2 2253:061568.385365 2253:061567.585982 INT0 R - running armed GNSS n/a valid 46892 1.3e-08 + // clang-format on + if (msg_size != UBX_TIM_TP_V0_SIZE) { + return 0; + } + UBX_TIM_TP_V0_GROUP0 tp; + std::memcpy(&tp, &msg[UBX_HEAD_SIZE], sizeof(tp)); + + const uint8_t timeBase = UBX_TIM_TP_V0_FLAGS_TIMEBASE_GET(tp.flags); + const double tow = + ((double)tp.towMs * UBX_TIM_TP_V0_TOWMS_SCALE) + ((double)tp.towSubMs * UBX_TIM_TP_V0_TOWSUBMS_SCALE); + const uint8_t timeRefGnss = UBX_TIM_TP_V0_REFINFO_TIMEREFGNSS_GET(tp.refInfo); + constexpr std::array timeRefGnssStr = { { "GPS", "GLO", "BDS", "GAL", "NAVIC" } }; + const uint8_t utcStandard = UBX_TIM_TP_V0_REFINFO_UTCSTANDARD_GET(tp.refInfo); + constexpr std::array utcStandardStr = { { "NA", "CRL", "NIST", "USNO", "BIPM", "EU", "SU", "NTSC", + "NPLI" } }; + + std::size_t ret = 0; + switch (timeBase) { + case UBX_TIM_TP_V0_FLAGS_TIMEBASE_GNSS: + ret = std::snprintf(info, size, "%019.12f GNSS %s", tow, + timeRefGnss < timeRefGnssStr.size() ? timeRefGnssStr[timeRefGnss] : "?"); + break; + case UBX_TIM_TP_V0_FLAGS_TIMEBASE_UTC: + ret = std::snprintf(info, size, "%019.12f UTC %s %s", tow, + UBX_TIM_TP_V0_FLAGS_UTC(tp.flags) ? "avail" : "n/a", + utcStandard < utcStandardStr.size() ? utcStandardStr[utcStandard] : "?"); + break; + default: + ret = std::snprintf(info, size, "%019.12f", tow); + break; + } + + if (ret < size) { + ret += std::snprintf(&info[ret], size - ret, " %d %c %c", tp.qErr, + UBX_TIM_TP_V0_FLAGS_QERRINVALID(tp.flags) ? 'Y' : 'N', + UBX_TIM_TP_V0_FLAGS_TPNOTLOCKED(tp.flags) ? 'U' : 'L'); + } + + return ret; +} + +static std::size_t StrUbxRxmRawx(char* info, const std::size_t size, const uint8_t* msg, const std::size_t msg_size) +{ + if ((UBX_RXM_RAWX_VERSION_GET(msg) != UBX_RXM_RAWX_V1_VERSION) || (msg_size != UBX_RXM_RAWX_V1_SIZE(msg))) { + return 0; + } + + UBX_RXM_RAWX_V1_GROUP0 rawx; + std::memcpy(&rawx, &msg[UBX_HEAD_SIZE], sizeof(rawx)); + return std::snprintf(info, size, "%010.3f %04u %u", rawx.rcvTow, rawx.week, rawx.numMeas); +} + +// --------------------------------------------------------------------------------------------------------------------- + +bool UbxGetMessageInfo(char* info, const std::size_t size, const uint8_t* msg, const std::size_t msg_size) +{ + if ((info == NULL) || (size < 1)) { + return false; + } + + if ((msg == NULL) || (msg_size < (UBX_HEAD_SIZE + 2))) { + info[0] = '\0'; + return false; + } + + if (msg_size == UBX_FRAME_SIZE) { + const std::size_t len = std::snprintf(info, size, "empty message / poll request"); + return (len > 0) && (len < size); + } + + const uint8_t cls_id = UbxClsId(msg); + const uint8_t msg_id = UbxMsgId(msg); + std::size_t len = 0; + switch (cls_id) { // clang-format off + case UBX_NAV_CLSID: switch (msg_id) { + case UBX_NAV_PVT_MSGID: len = StrUbxNavPvt(info, size, msg, msg_size); break; + case UBX_NAV_POSECEF_MSGID: len = StrUbxNavPosecef(info, size, msg, msg_size); break; + case UBX_NAV_HPPOSECEF_MSGID: len = StrUbxNavHpposecef(info, size, msg, msg_size); break; + case UBX_NAV_RELPOSNED_MSGID: len = StrUbxNavRelposned(info, size, msg, msg_size); break; + case UBX_NAV_STATUS_MSGID: len = StrUbxNavStatus(info, size, msg, msg_size); break; + case UBX_NAV_SAT_MSGID: len = StrUbxNavSat(info, size, msg, msg_size); break; + case UBX_NAV_SIG_MSGID: len = StrUbxNavSig(info, size, msg, msg_size); break; + case UBX_NAV_TIMEGPS_MSGID: len = StrUbxNavTimegps(info, size, msg, msg_size); break; + case UBX_NAV_TIMEGAL_MSGID: len = StrUbxNavTimegal(info, size, msg, msg_size); break; + case UBX_NAV_TIMEBDS_MSGID: len = StrUbxNavTimebds(info, size, msg, msg_size); break; + case UBX_NAV_TIMEGLO_MSGID: len = StrUbxNavTimeglo(info, size, msg, msg_size); break; + case UBX_NAV_TIMEUTC_MSGID: len = StrUbxNavTimeutc(info, size, msg, msg_size); break; + case UBX_NAV_ORB_MSGID: /* FALLTHROUGH */ + case UBX_NAV_CLOCK_MSGID: /* FALLTHROUGH */ + case UBX_NAV_DOP_MSGID: /* FALLTHROUGH */ + case UBX_NAV_POSLLH_MSGID: /* FALLTHROUGH */ + case UBX_NAV_VELECEF_MSGID: /* FALLTHROUGH */ + case UBX_NAV_VELNED_MSGID: /* FALLTHROUGH */ + case UBX_NAV_EOE_MSGID: /* FALLTHROUGH */ + case UBX_NAV_GEOFENCE_MSGID: /* FALLTHROUGH */ + case UBX_NAV_TIMELS_MSGID: /* FALLTHROUGH */ + case UBX_NAV_COV_MSGID: len = StrUbxNav(info, size, msg, msg_size, 0); break; + case UBX_NAV_SVIN_MSGID: /* FALLTHROUGH */ + case UBX_NAV_ODO_MSGID: /* FALLTHROUGH */ + case UBX_NAV_HPPOSLLH_MSGID: len = StrUbxNav(info, size, msg, msg_size, 4); break; } break; + case UBX_INF_CLSID: len = StrUbxInf(info, size, msg, msg_size); break; + case UBX_RXM_CLSID: switch (msg_id) { + case UBX_RXM_RAWX_MSGID: len = StrUbxRxmRawx(info, size, msg, msg_size); break; + case UBX_RXM_SFRBX_MSGID: len = StrUbxRxmSfrbx(info, size, msg, msg_size); break; } break; + case UBX_MON_CLSID: switch (msg_id) { + case UBX_MON_VER_MSGID: len = StrUbxMonVer(info, size, msg, msg_size); break; + case UBX_MON_TEMP_MSGID: len = StrUbxMonTemp(info, size, msg, msg_size); break; } break; + case UBX_CFG_CLSID: switch (msg_id) { + case UBX_CFG_VALSET_MSGID: len = StrUbxCfgValset(info, size, msg, msg_size); break; + case UBX_CFG_VALGET_MSGID: len = StrUbxCfgValget(info, size, msg, msg_size); break; } break; + case UBX_ACK_CLSID: switch (msg_id) { + case UBX_ACK_ACK_MSGID: len = StrUbxAckAck(info, size, msg, msg_size, true); break; + case UBX_ACK_NAK_MSGID: len = StrUbxAckAck(info, size, msg, msg_size, false); break; } break; + case UBX_TIM_CLSID: switch (msg_id) { + case UBX_TIM_TM2_MSGID: len = StrUbxTimTm2(info, size, msg, msg_size); break; + case UBX_TIM_TP_MSGID: len = StrUbxTimTp(info, size, msg, msg_size); break; } break; + } // clang-format off + + // @todo insert ellipsis instead of failing in case len > size ? + return (len > 0) && (len < size); +} + +/* ****************************************************************************************************************** */ +} // namespace ubx +} // namespace parser +} // namespace common +} // namespace fpsdk diff --git a/fpsdk_common/src/parser/unib.cpp b/fpsdk_common/src/parser/unib.cpp new file mode 100644 index 0000000..7d92454 --- /dev/null +++ b/fpsdk_common/src/parser/unib.cpp @@ -0,0 +1,237 @@ +/** + * \verbatim + * ___ ___ + * \ \ / / + * \ \/ / Copyright (c) Fixposition AG (www.fixposition.com) and contributors + * / /\ \ License: see the LICENSE file + * /__/ \__\ + * + * Based on work by flipflip (https://github.com/phkehl) + * \endverbatim + * + * @file + * @brief Fixposition SDK: Parser UNI_B routines and types + */ + +/* LIBC/STL */ +#include +#include +#include +#include +#include + +/* EXTERNAL */ + +/* PACKAGE */ +#include "fpsdk_common/parser/unib.hpp" + +namespace fpsdk { +namespace common { +namespace parser { +namespace unib { +/* ****************************************************************************************************************** */ + +// Lookup table entry +struct MsgInfo +{ + uint16_t msg_id; + const char* name; +}; + +// clang-format off +// @fp_codegen_begin{FPSDK_COMMON_PARSER_UNIB_MSGINFO} +static constexpr std::array MSG_INFO = +{{ + { UNI_B_VERSION_MSGID, UNI_B_VERSION_STRID }, + { UNI_B_OBSVM_MSGID, UNI_B_OBSVM_STRID }, + { UNI_B_OBSVH_MSGID, UNI_B_OBSVH_STRID }, + { UNI_B_OBSVMCMP_MSGID, UNI_B_OBSVMCMP_STRID }, + { UNI_B_OBSVHCMP_MSGID, UNI_B_OBSVHCMP_STRID }, + { UNI_B_OBSVBASE_MSGID, UNI_B_OBSVBASE_STRID }, + { UNI_B_BASEINFO_MSGID, UNI_B_BASEINFO_STRID }, + { UNI_B_GPSION_MSGID, UNI_B_GPSION_STRID }, + { UNI_B_BD3ION_MSGID, UNI_B_BD3ION_STRID }, + { UNI_B_BDSION_MSGID, UNI_B_BDSION_STRID }, + { UNI_B_GALION_MSGID, UNI_B_GALION_STRID }, + { UNI_B_GPSUTC_MSGID, UNI_B_GPSUTC_STRID }, + { UNI_B_BD3UTC_MSGID, UNI_B_BD3UTC_STRID }, + { UNI_B_BDSUTC_MSGID, UNI_B_BDSUTC_STRID }, + { UNI_B_GALUTC_MSGID, UNI_B_GALUTC_STRID }, + { UNI_B_GPSEPH_MSGID, UNI_B_GPSEPH_STRID }, + { UNI_B_QZSSEPH_MSGID, UNI_B_QZSSEPH_STRID }, + { UNI_B_BD3EPH_MSGID, UNI_B_BD3EPH_STRID }, + { UNI_B_BDSEPH_MSGID, UNI_B_BDSEPH_STRID }, + { UNI_B_GLOEPH_MSGID, UNI_B_GLOEPH_STRID }, + { UNI_B_GALEPH_MSGID, UNI_B_GALEPH_STRID }, + { UNI_B_AGRIC_MSGID, UNI_B_AGRIC_STRID }, + { UNI_B_PVTSLN_MSGID, UNI_B_PVTSLN_STRID }, + { UNI_B_BESTNAV_MSGID, UNI_B_BESTNAV_STRID }, + { UNI_B_BESTNAVXYZ_MSGID, UNI_B_BESTNAVXYZ_STRID }, + { UNI_B_BESTNAVH_MSGID, UNI_B_BESTNAVH_STRID }, + { UNI_B_BESTNAVXYZH_MSGID, UNI_B_BESTNAVXYZH_STRID }, + { UNI_B_BESTSAT_MSGID, UNI_B_BESTSAT_STRID }, + { UNI_B_ADRNAV_MSGID, UNI_B_ADRNAV_STRID }, + { UNI_B_ADRNAVH_MSGID, UNI_B_ADRNAVH_STRID }, + { UNI_B_PPPNAV_MSGID, UNI_B_PPPNAV_STRID }, + { UNI_B_SPPNAV_MSGID, UNI_B_SPPNAV_STRID }, + { UNI_B_SPPNAVH_MSGID, UNI_B_SPPNAVH_STRID }, + { UNI_B_STADOP_MSGID, UNI_B_STADOP_STRID }, + { UNI_B_STADOPH_MSGID, UNI_B_STADOPH_STRID }, + { UNI_B_ADRDOP_MSGID, UNI_B_ADRDOP_STRID }, + { UNI_B_ADRDOPH_MSGID, UNI_B_ADRDOPH_STRID }, + { UNI_B_PPPDOP_MSGID, UNI_B_PPPDOP_STRID }, + { UNI_B_SPPDOP_MSGID, UNI_B_SPPDOP_STRID }, + { UNI_B_SPPDOPH_MSGID, UNI_B_SPPDOPH_STRID }, + { UNI_B_SATSINFO_MSGID, UNI_B_SATSINFO_STRID }, + { UNI_B_BASEPOS_MSGID, UNI_B_BASEPOS_STRID }, + { UNI_B_SATELLITE_MSGID, UNI_B_SATELLITE_STRID }, + { UNI_B_SATECEF_MSGID, UNI_B_SATECEF_STRID }, + { UNI_B_RECTIME_MSGID, UNI_B_RECTIME_STRID }, + { UNI_B_NOVHEADING_MSGID, UNI_B_NOVHEADING_STRID }, + { UNI_B_NOVHEADING2_MSGID, UNI_B_NOVHEADING2_STRID }, + { UNI_B_RTKSTATUS_MSGID, UNI_B_RTKSTATUS_STRID }, + { UNI_B_AGNSSSTATUS_MSGID, UNI_B_AGNSSSTATUS_STRID }, + { UNI_B_RTCSTATUS_MSGID, UNI_B_RTCSTATUS_STRID }, + { UNI_B_JAMSTATUS_MSGID, UNI_B_JAMSTATUS_STRID }, + { UNI_B_FREQJAMSTATUS_MSGID, UNI_B_FREQJAMSTATUS_STRID }, + { UNI_B_RTCMSTATUS_MSGID, UNI_B_RTCMSTATUS_STRID }, + { UNI_B_HWSTATUS_MSGID, UNI_B_HWSTATUS_STRID }, + { UNI_B_PPPSTATUS_MSGID, UNI_B_PPPSTATUS_STRID }, + { UNI_B_AGC_MSGID, UNI_B_AGC_STRID }, + { UNI_B_INFOPART1_MSGID, UNI_B_INFOPART1_STRID }, + { UNI_B_INFOPART2_MSGID, UNI_B_INFOPART2_STRID }, + { UNI_B_MSPOS_MSGID, UNI_B_MSPOS_STRID }, + { UNI_B_TROPINFO_MSGID, UNI_B_TROPINFO_STRID }, + { UNI_B_PTOBSINFO_MSGID, UNI_B_PTOBSINFO_STRID }, + { UNI_B_PPPB2INFO1_MSGID, UNI_B_PPPB2INFO1_STRID }, + { UNI_B_PPPB2INFO2_MSGID, UNI_B_PPPB2INFO2_STRID }, + { UNI_B_PPPB2INFO3_MSGID, UNI_B_PPPB2INFO3_STRID }, + { UNI_B_PPPB2INFO4_MSGID, UNI_B_PPPB2INFO4_STRID }, + { UNI_B_PPPB2INFO5_MSGID, UNI_B_PPPB2INFO5_STRID }, + { UNI_B_PPPB2INFO6_MSGID, UNI_B_PPPB2INFO6_STRID }, + { UNI_B_PPPB2INFO7_MSGID, UNI_B_PPPB2INFO7_STRID }, +}}; +// @fp_codegen_end{FPSDK_COMMON_PARSER_UNIB_MSGINFO} +// clang-format on + +bool UnibGetMessageName(char* name, const std::size_t size, const uint8_t* msg, const std::size_t msg_size) +{ + // Check arguments + if ((name == NULL) || (size < 1)) { + return false; + } + name[0] = '\0'; + + if ((msg == NULL) || (msg_size < sizeof(UnibHeader))) { + return false; + } + + const uint16_t msg_id = UnibMsgId(msg); + + // Try the message name lookup table + for (auto& info : MSG_INFO) { + if (info.msg_id == msg_id) { + return std::snprintf(name, size, "%s", info.name) < (int)size; + } + } + + // If that failed, too, stringify the message ID + return std::snprintf(name, size, "UNI_B-MSG%05" PRIu16, msg_id) < (int)size; +} + +// --------------------------------------------------------------------------------------------------------------------- + +const char* UnibTimeRefStr(const UnibTimeRef time_ref) +{ + switch (time_ref) { // clang-format off + case UnibTimeRef::GPST: return "GPST"; + case UnibTimeRef::BDST: return "BDST"; + } // clang-format on + return "?"; +} + +// --------------------------------------------------------------------------------------------------------------------- + +const char* UnibTimeStatusStr(const UnibTimeStatus time_status) +{ + switch (time_status) { // clang-format off + case UnibTimeStatus::UNKNOWN: return "UNKNOWN"; + case UnibTimeStatus::FINE: return "FINE"; + } // clang-format on + return "?"; +} + +// --------------------------------------------------------------------------------------------------------------------- + +const char* UnibProductModelStr(const UnibProductModel model) +{ + switch (model) { // clang-format off + case UnibProductModel::UNKNOWN: return "UNKNOWN"; + case UnibProductModel::UB4B0: return "UB4B0"; + case UnibProductModel::UM4B0: return "UM4B0"; + case UnibProductModel::UM480: return "UM480"; + case UnibProductModel::UM440: return "UM440"; + case UnibProductModel::UM482: return "UM482"; + case UnibProductModel::UM442: return "UM442"; + case UnibProductModel::UB482: return "UB482"; + case UnibProductModel::UT4B0: return "UT4B0"; + case UnibProductModel::UB362L: return "UB362L"; + case UnibProductModel::UB4B0M: return "UB4B0M"; + case UnibProductModel::UB4B0J: return "UB4B0J"; + case UnibProductModel::UM482L: return "UM482L"; + case UnibProductModel::UM4B0L: return "UM4B0L"; + case UnibProductModel::CLAP_B: return "CLAP_B"; + case UnibProductModel::UM982: return "UM982"; + case UnibProductModel::UM980: return "UM980"; + case UnibProductModel::UM960: return "UM960"; + case UnibProductModel::UM980A: return "UM980A"; + case UnibProductModel::CLAP_C: return "CLAP_C"; + case UnibProductModel::UM960L: return "UM960L"; + case UnibProductModel::UM981: return "UM981"; + } + return "?"; // not the same as "UNKNOWN"! +} + +// --------------------------------------------------------------------------------------------------------------------- + +// static int StrUnibSome(char *info, const std::size_t size, const uint8_t *msg, const int msg_size) +// { +// int len = 0; +// // ... +// return len; +// } + +// --------------------------------------------------------------------------------------------------------------------- + +bool UnibGetMessageInfo(char* info, const std::size_t size, const uint8_t* msg, const std::size_t msg_size) +{ + if ((info == NULL) || (size < 1)) { + return false; + } + + if ((msg == NULL) || (msg_size < UNI_B_HEAD_SIZE)) { + info[0] = '\0'; + return false; + } + std::size_t len = 0; + + // Common stringification + UnibHeader hdr; + std::memcpy(&hdr, msg, sizeof(hdr)); + len += snprintf(&info[len], size - len, "l %010.3f", (double)hdr.tow_ms * 1e-3); + + // Specific stringification for some messages + // switch (UnibMsgId(msg)) { + // case UNI_B_SOME_MSGID: + // len += StrUnibSome(&info[len], size - len, msg, msg_size); + // break; + // } + + return (len > 0) && (len < size); +} + +/* ****************************************************************************************************************** */ +} // namespace unib +} // namespace parser +} // namespace common +} // namespace fpsdk diff --git a/fpsdk_common/src/path.cpp b/fpsdk_common/src/path.cpp index 35f3576..9b69d01 100644 --- a/fpsdk_common/src/path.cpp +++ b/fpsdk_common/src/path.cpp @@ -72,7 +72,7 @@ bool OutputFile::Open(const std::string& path) fh_ = std::make_unique(path, std::ios::binary); } if (fh_->fail()) { - WARNING("OutputFile: open fail %s: %s", path.c_str(), std::strerror(errno)); + WARNING("OutputFile: open fail %s: %s", path.c_str(), string::StrError(errno).c_str()); fh_.reset(); return false; } @@ -106,7 +106,7 @@ bool OutputFile::Write(const uint8_t* data, const std::size_t size) bool ok = true; fh_->write((const char*)data, size); if (fh_->fail()) { - WARNING("OutputFile: write fail %s: %s", path_.c_str(), std::strerror(errno)); + WARNING("OutputFile: write fail %s: %s", path_.c_str(), string::StrError(errno).c_str()); ok = false; } return ok; @@ -118,7 +118,7 @@ bool FileSlurp(const std::string& path, std::vector& data) { std::ifstream fh(path, std::ios::binary); if (fh.fail()) { - WARNING("FileSlurp: fail open %s: %s", path.c_str(), std::strerror(errno)); + WARNING("FileSlurp: fail open %s: %s", path.c_str(), string::StrError(errno).c_str()); return false; } @@ -129,7 +129,7 @@ bool FileSlurp(const std::string& path, std::vector& data) } bool ok = true; if (!fh.eof() && fh.fail()) { - WARNING("FileSlurp: fail read %s: %s", path.c_str(), std::strerror(errno)); + WARNING("FileSlurp: fail read %s: %s", path.c_str(), string::StrError(errno).c_str()); ok = false; } @@ -143,14 +143,14 @@ bool FileSpew(const std::string& path, const std::vector& data) { std::ofstream fh(path, std::ios::binary); if (fh.fail()) { - WARNING("FileSpew: fail open %s: %s", path.c_str(), std::strerror(errno)); + WARNING("FileSpew: fail open %s: %s", path.c_str(), string::StrError(errno).c_str()); return false; } fh.write((const char*)data.data(), data.size()); bool ok = true; if (fh.fail()) { - WARNING("FileSlurp: fail write %s: %s", path.c_str(), std::strerror(errno)); + WARNING("FileSlurp: fail write %s: %s", path.c_str(), string::StrError(errno).c_str()); ok = false; } diff --git a/fpsdk_common/src/string.cpp b/fpsdk_common/src/string.cpp index 0b2e4b7..d6c6637 100644 --- a/fpsdk_common/src/string.cpp +++ b/fpsdk_common/src/string.cpp @@ -445,6 +445,20 @@ std::string StrToLower(const std::string& str) return res; } +// --------------------------------------------------------------------------------------------------------------------- + +std::string StrError(const int errnum) +{ +#if __GLIBC_PREREQ(2, 32) + const char* desc = strerrordesc_np(errnum); + const char* name = strerrorname_np(errnum); + return Sprintf("%s (%d, %s)", desc == NULL ? "Unknown error" : desc, errnum, name == NULL ? "?" : name); +#else + char buf[1000]; + return Sprintf("%s (%d)", strerror_r(errnum, buf, sizeof(buf)), errnum); +#endif +} + /* ****************************************************************************************************************** */ } // namespace string } // namespace common diff --git a/fpsdk_common/src/thread.cpp b/fpsdk_common/src/thread.cpp index 25bbbf4..df10a65 100644 --- a/fpsdk_common/src/thread.cpp +++ b/fpsdk_common/src/thread.cpp @@ -127,7 +127,7 @@ void Thread::_Thread() try { func_(this, arg_); } catch (const std::exception& e) { - WARNING("%s thread crash: %s", name_.c_str(), e.what()); + WARNING("%s thread unhandled exception: %s", name_.c_str(), e.what()); } // Run optional user cleanup function diff --git a/fpsdk_common/src/trafo.cpp b/fpsdk_common/src/trafo.cpp index 73df53d..6c15fc4 100644 --- a/fpsdk_common/src/trafo.cpp +++ b/fpsdk_common/src/trafo.cpp @@ -33,20 +33,6 @@ namespace trafo { using namespace fpsdk::common::math; using namespace fpsdk::common::string; -/** - * @details - * - * \f[ - * - * \text{Rotate a vector from ECEF to ENU:} \\ - * V_{ENU} = M \cdot V_{ECEF} \\ - * \text{Rotate a covariance matrix from ECEF to ENU:} \\ - * Cov_{ENU} = M \cdot Cov_{ECEF} \cdot M^{T} \\ - * - * \f] - * - * Reference https://gssc.esa.int/navipedia/index.php/Transformations_between_ECEF_and_ENU_coordinates - */ Eigen::Matrix3d RotEnuEcef(const double lat, const double lon) { const double s_lon = sin(lon); @@ -72,18 +58,6 @@ Eigen::Matrix3d RotEnuEcef(const double lat, const double lon) // --------------------------------------------------------------------------------------------------------------------- -/** - * @details - * - * \f[ - * - * \text{Rotate a vector from ECEF to ENU:} \\ - * V_{ENU} = M \cdot V_{ECEF} \\ - * \text{Rotate a covariance matrix from ECEF to ENU:} \\ - * Cov_{ENU} = M \cdot Cov_{ECEF} \cdot M^{T} \\ - * - * \f] - */ Eigen::Matrix3d RotEnuEcef(const Eigen::Vector3d& ecef) { const Eigen::Vector3d wgs84llh = TfWgs84LlhEcef(ecef); diff --git a/fpsdk_common/src/types.cpp b/fpsdk_common/src/types.cpp index d4501e9..c136aa4 100644 --- a/fpsdk_common/src/types.cpp +++ b/fpsdk_common/src/types.cpp @@ -23,26 +23,6 @@ namespace common { namespace types { /* ****************************************************************************************************************** */ -const char* GnssFixTypeStr(const GnssFixType fix_type) -{ - switch (fix_type) { - // clang-format off - case GnssFixType::FIX_UNKNOWN: return "FIX_UNKNOWN"; - case GnssFixType::FIX_NOFIX: return "FIX_NOFIX"; - case GnssFixType::FIX_DRONLY: return "FIX_DRONLY"; - case GnssFixType::FIX_TIME: return "FIX_TIME"; - case GnssFixType::FIX_2D: return "FIX_2D"; - case GnssFixType::FIX_3D: return "FIX_3D"; - case GnssFixType::FIX_3D_DR: return "FIX_3D_DR"; - case GnssFixType::FIX_RTK_FLOAT: return "FIX_RTK_FLOAT"; - case GnssFixType::FIX_RTK_FIXED: return "FIX_RTK_FIXED"; - case GnssFixType::FIX_RTK_FLOAT_DR: return "FIX_RTK_FLOAT_DR"; - case GnssFixType::FIX_RTK_FIXED_DR: return "FIX_RTK_FIXED_DR"; - // clang-format on - } - return "?"; -} - /* ****************************************************************************************************************** */ } // namespace types } // namespace common diff --git a/fpsdk_common/test/data/Makefile b/fpsdk_common/test/data/Makefile new file mode 100644 index 0000000..710773f --- /dev/null +++ b/fpsdk_common/test/data/Makefile @@ -0,0 +1,22 @@ +INPUTS := $(wildcard *.bin) +OUTPUTS := $(patsubst %.bin, %.cpp, $(INPUTS)) + +# $ (info INPUTS=$(INPUTS)) +# $ (info OUTPUTS=$(OUTPUTS)) + +all: $(OUTPUTS) + +.SUFFIXES: + +%.cpp: %.bin Makefile + @echo "$< -> $@" + @echo -n > $@.tmp + @echo "// clang-format off" >> $@.tmp + @xxd -i -C -c 32 $< \ + | sed -e 's/unsigned char/static const std::vector/' -e 's/\[\]//' -e '/unsigned int/d' \ + >> $@.tmp + @mv $@.tmp $@ + + + + diff --git a/fpsdk_common/test/data/test_data_fpa.bin b/fpsdk_common/test/data/test_data_fpa.bin new file mode 100644 index 0000000..2fc2f1b --- /dev/null +++ b/fpsdk_common/test/data/test_data_fpa.bin @@ -0,0 +1,2 @@ +$FP,ODOMETRY,2,2253,323299.100000,,,,,,,,,,,,,,,,,0,0,8,8,-1,,,,,,,,,,,,,,,,,,,fp_release_vr2_2.63.1_204*7B +$FP,TF,2,2253,323299.000000,VRTK,CAM,-0.03400,0.00200,-0.01600,-0.000000,0.000000,0.000000,1.000000*66 diff --git a/fpsdk_common/test/data/test_data_fpa.cpp b/fpsdk_common/test/data/test_data_fpa.cpp new file mode 100644 index 0000000..04ae174 --- /dev/null +++ b/fpsdk_common/test/data/test_data_fpa.cpp @@ -0,0 +1,10 @@ +// clang-format off +static const std::vector TEST_DATA_FPA_BIN = { + 0x24, 0x46, 0x50, 0x2c, 0x4f, 0x44, 0x4f, 0x4d, 0x45, 0x54, 0x52, 0x59, 0x2c, 0x32, 0x2c, 0x32, 0x32, 0x35, 0x33, 0x2c, 0x33, 0x32, 0x33, 0x32, 0x39, 0x39, 0x2e, 0x31, 0x30, 0x30, 0x30, 0x30, + 0x30, 0x2c, 0x2c, 0x2c, 0x2c, 0x2c, 0x2c, 0x2c, 0x2c, 0x2c, 0x2c, 0x2c, 0x2c, 0x2c, 0x2c, 0x2c, 0x2c, 0x2c, 0x30, 0x2c, 0x30, 0x2c, 0x38, 0x2c, 0x38, 0x2c, 0x2d, 0x31, 0x2c, 0x2c, 0x2c, 0x2c, + 0x2c, 0x2c, 0x2c, 0x2c, 0x2c, 0x2c, 0x2c, 0x2c, 0x2c, 0x2c, 0x2c, 0x2c, 0x2c, 0x2c, 0x2c, 0x66, 0x70, 0x5f, 0x72, 0x65, 0x6c, 0x65, 0x61, 0x73, 0x65, 0x5f, 0x76, 0x72, 0x32, 0x5f, 0x32, 0x2e, + 0x36, 0x33, 0x2e, 0x31, 0x5f, 0x32, 0x30, 0x34, 0x2a, 0x37, 0x42, 0x0d, 0x0a, 0x24, 0x46, 0x50, 0x2c, 0x54, 0x46, 0x2c, 0x32, 0x2c, 0x32, 0x32, 0x35, 0x33, 0x2c, 0x33, 0x32, 0x33, 0x32, 0x39, + 0x39, 0x2e, 0x30, 0x30, 0x30, 0x30, 0x30, 0x30, 0x2c, 0x56, 0x52, 0x54, 0x4b, 0x2c, 0x43, 0x41, 0x4d, 0x2c, 0x2d, 0x30, 0x2e, 0x30, 0x33, 0x34, 0x30, 0x30, 0x2c, 0x30, 0x2e, 0x30, 0x30, 0x32, + 0x30, 0x30, 0x2c, 0x2d, 0x30, 0x2e, 0x30, 0x31, 0x36, 0x30, 0x30, 0x2c, 0x2d, 0x30, 0x2e, 0x30, 0x30, 0x30, 0x30, 0x30, 0x30, 0x2c, 0x30, 0x2e, 0x30, 0x30, 0x30, 0x30, 0x30, 0x30, 0x2c, 0x30, + 0x2e, 0x30, 0x30, 0x30, 0x30, 0x30, 0x30, 0x2c, 0x31, 0x2e, 0x30, 0x30, 0x30, 0x30, 0x30, 0x30, 0x2a, 0x36, 0x36, 0x0d, 0x0a +}; diff --git a/fpsdk_common/test/data/test_data_fpb.bin b/fpsdk_common/test/data/test_data_fpb.bin new file mode 100644 index 0000000..7ceec44 Binary files /dev/null and b/fpsdk_common/test/data/test_data_fpb.bin differ diff --git a/fpsdk_common/test/data/test_data_fpb.cpp b/fpsdk_common/test/data/test_data_fpb.cpp new file mode 100644 index 0000000..9a690e3 --- /dev/null +++ b/fpsdk_common/test/data/test_data_fpb.cpp @@ -0,0 +1,7 @@ +// clang-format off +static const std::vector TEST_DATA_FPB_BIN = { + 0x66, 0x21, 0xd1, 0x07, 0x5c, 0x00, 0x00, 0x00, 0x01, 0x03, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x0a, 0x00, 0x00, 0x00, 0x14, 0x00, 0x00, 0x00, 0xe2, 0xff, 0xff, 0xff, 0x01, 0x01, 0x01, 0x01, + 0x01, 0x00, 0x00, 0x00, 0x00, 0x01, 0x0a, 0x00, 0x4e, 0x61, 0xbc, 0x00, 0x0b, 0x00, 0x00, 0x00, 0x15, 0x00, 0x00, 0x00, 0xe3, 0xff, 0xff, 0xff, 0x01, 0x01, 0x01, 0x01, 0x02, 0x00, 0x00, 0x00, + 0x00, 0x01, 0x0a, 0x00, 0x4e, 0x61, 0xbc, 0x00, 0x0c, 0x00, 0x00, 0x00, 0x16, 0x00, 0x00, 0x00, 0xe4, 0xff, 0xff, 0xff, 0x01, 0x01, 0x01, 0x01, 0x03, 0x00, 0x00, 0x00, 0x00, 0x01, 0x0a, 0x00, + 0x4e, 0x61, 0xbc, 0x00, 0x26, 0x54, 0xaa, 0x34 +}; diff --git a/fpsdk_common/test/data/test_data_mixed.bin b/fpsdk_common/test/data/test_data_mixed.bin new file mode 100644 index 0000000..8ce85bc Binary files /dev/null and b/fpsdk_common/test/data/test_data_mixed.bin differ diff --git a/fpsdk_common/test/data/test_data_mixed.cpp b/fpsdk_common/test/data/test_data_mixed.cpp new file mode 100644 index 0000000..176a91b --- /dev/null +++ b/fpsdk_common/test/data/test_data_mixed.cpp @@ -0,0 +1,92 @@ +// clang-format off +static const std::vector TEST_DATA_MIXED_BIN = { + 0x24, 0x46, 0x50, 0x2c, 0x4f, 0x44, 0x4f, 0x4d, 0x45, 0x54, 0x52, 0x59, 0x2c, 0x32, 0x2c, 0x32, 0x32, 0x35, 0x33, 0x2c, 0x33, 0x32, 0x33, 0x32, 0x39, 0x39, 0x2e, 0x31, 0x30, 0x30, 0x30, 0x30, + 0x30, 0x2c, 0x2c, 0x2c, 0x2c, 0x2c, 0x2c, 0x2c, 0x2c, 0x2c, 0x2c, 0x2c, 0x2c, 0x2c, 0x2c, 0x2c, 0x2c, 0x2c, 0x30, 0x2c, 0x30, 0x2c, 0x38, 0x2c, 0x38, 0x2c, 0x2d, 0x31, 0x2c, 0x2c, 0x2c, 0x2c, + 0x2c, 0x2c, 0x2c, 0x2c, 0x2c, 0x2c, 0x2c, 0x2c, 0x2c, 0x2c, 0x2c, 0x2c, 0x2c, 0x2c, 0x2c, 0x66, 0x70, 0x5f, 0x72, 0x65, 0x6c, 0x65, 0x61, 0x73, 0x65, 0x5f, 0x76, 0x72, 0x32, 0x5f, 0x32, 0x2e, + 0x36, 0x33, 0x2e, 0x31, 0x5f, 0x32, 0x30, 0x34, 0x2a, 0x37, 0x42, 0x0d, 0x0a, 0x24, 0x47, 0x4e, 0x52, 0x4d, 0x43, 0x2c, 0x31, 0x37, 0x34, 0x36, 0x34, 0x34, 0x2e, 0x32, 0x30, 0x2c, 0x41, 0x2c, + 0x34, 0x37, 0x32, 0x34, 0x2e, 0x30, 0x31, 0x38, 0x31, 0x38, 0x2c, 0x4e, 0x2c, 0x30, 0x30, 0x38, 0x32, 0x37, 0x2e, 0x30, 0x32, 0x32, 0x34, 0x34, 0x2c, 0x45, 0x2c, 0x30, 0x2e, 0x30, 0x31, 0x33, + 0x2c, 0x2c, 0x31, 0x35, 0x30, 0x33, 0x32, 0x33, 0x2c, 0x2c, 0x2c, 0x52, 0x2c, 0x56, 0x2a, 0x30, 0x44, 0x0d, 0x0a, 0xaa, 0x44, 0x12, 0x1c, 0x2a, 0x00, 0x00, 0xa0, 0x48, 0x00, 0x00, 0x00, 0x23, + 0xb4, 0x83, 0x08, 0x64, 0xdb, 0x68, 0x0c, 0x00, 0x08, 0x00, 0x03, 0xba, 0xcd, 0x19, 0x40, 0x00, 0x00, 0x00, 0x00, 0x38, 0x00, 0x00, 0x00, 0xcf, 0x6a, 0x48, 0x15, 0x4c, 0xb3, 0x47, 0x40, 0xe6, + 0xeb, 0x19, 0x6b, 0xb8, 0xe3, 0x20, 0x40, 0x00, 0x00, 0x58, 0x31, 0xd2, 0x84, 0x78, 0x40, 0x66, 0x66, 0x3e, 0x42, 0x3d, 0x00, 0x00, 0x00, 0x85, 0x2d, 0x11, 0x3d, 0xf3, 0xd6, 0x04, 0x3d, 0xc6, + 0x57, 0x52, 0x3d, 0x30, 0x00, 0x00, 0x00, 0x00, 0x00, 0x80, 0x3f, 0x00, 0x00, 0x00, 0x00, 0x16, 0x15, 0x15, 0x10, 0x00, 0x21, 0x15, 0x33, 0x3f, 0x6c, 0xbc, 0xfe, 0xe5, 0x60, 0x12, 0x2f, 0x97, + 0x8c, 0x5e, 0x1c, 0x51, 0x01, 0xb8, 0xd1, 0xe2, 0x33, 0x15, 0xed, 0xcd, 0x96, 0x2e, 0x36, 0x66, 0x32, 0x51, 0xf5, 0xa7, 0x6a, 0x40, 0x5e, 0x38, 0x13, 0xd7, 0xf4, 0xba, 0x78, 0xb3, 0x98, 0xce, + 0x6c, 0x8f, 0x4e, 0x32, 0x2c, 0xd3, 0x00, 0x16, 0x45, 0x30, 0x00, 0x4d, 0x10, 0x93, 0xa2, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x1f, 0x9b, + 0x2f, 0x73, 0x00, 0x10, 0xe3, 0x18, 0xb9, 0xa1, 0x8d, 0x68, 0x5b, 0x1f, 0x88, 0xa0, 0xba, 0xc2, 0x37, 0x43, 0xeb, 0x3f, 0xbe, 0x08, 0xf8, 0x51, 0x7f, 0x3a, 0x9a, 0x78, 0x32, 0x85, 0xc6, 0xe2, + 0xd0, 0x7e, 0xee, 0x37, 0xcb, 0x3d, 0x6a, 0x8f, 0xf1, 0x4c, 0x27, 0x43, 0x0d, 0x2a, 0x70, 0xf2, 0x01, 0xb5, 0x62, 0x0d, 0x01, 0x10, 0x00, 0x88, 0xb7, 0x43, 0x13, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0xcd, 0x08, 0x1b, 0x3f, 0xe2, 0xd2, 0xd3, 0x00, 0x16, 0x45, 0x30, 0x00, 0x4d, 0x10, 0x93, 0xa2, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x24, 0x46, 0x50, + 0x2c, 0x54, 0x46, 0x2c, 0x32, 0x2c, 0x32, 0x32, 0x35, 0x33, 0x2c, 0x33, 0x32, 0x33, 0x32, 0x39, 0x39, 0x2e, 0x30, 0x30, 0x30, 0x30, 0x30, 0x30, 0x2c, 0x56, 0x52, 0x54, 0x4b, 0x2c, 0x43, 0x41, + 0x4d, 0x2c, 0x2d, 0x30, 0x2e, 0x30, 0x33, 0x34, 0x30, 0x30, 0x2c, 0x30, 0x2e, 0x30, 0x30, 0x32, 0x30, 0x30, 0x2c, 0x2d, 0x30, 0x2e, 0x30, 0x31, 0x36, 0x30, 0x30, 0x2c, 0x2d, 0x30, 0x2e, 0x30, + 0x30, 0x30, 0x30, 0x30, 0x30, 0x2c, 0x30, 0x2e, 0x30, 0x30, 0x30, 0x30, 0x30, 0x30, 0x2c, 0x30, 0x2e, 0x30, 0x30, 0x30, 0x30, 0x30, 0x30, 0x2c, 0x31, 0x2e, 0x30, 0x30, 0x30, 0x30, 0x30, 0x30, + 0x2a, 0x36, 0x36, 0x0d, 0x0a, 0x24, 0x47, 0x4e, 0x47, 0x47, 0x41, 0x2c, 0x31, 0x37, 0x34, 0x36, 0x34, 0x34, 0x2e, 0x32, 0x30, 0x2c, 0x34, 0x37, 0x32, 0x34, 0x2e, 0x30, 0x31, 0x38, 0x31, 0x38, + 0x2c, 0x4e, 0x2c, 0x30, 0x30, 0x38, 0x32, 0x37, 0x2e, 0x30, 0x32, 0x32, 0x34, 0x34, 0x2c, 0x45, 0x2c, 0x34, 0x2c, 0x31, 0x32, 0x2c, 0x30, 0x2e, 0x35, 0x38, 0x2c, 0x34, 0x31, 0x32, 0x2e, 0x31, + 0x2c, 0x4d, 0x2c, 0x34, 0x37, 0x2e, 0x33, 0x2c, 0x4d, 0x2c, 0x31, 0x2e, 0x32, 0x2c, 0x30, 0x30, 0x30, 0x30, 0x2a, 0x36, 0x43, 0x0d, 0x0a, 0xaa, 0x44, 0x12, 0x1c, 0xf1, 0x00, 0x00, 0xa0, 0x70, + 0x00, 0x00, 0x00, 0x23, 0xb4, 0x83, 0x08, 0x64, 0xdb, 0x68, 0x0c, 0x00, 0x08, 0x00, 0x03, 0xcf, 0x44, 0x19, 0x40, 0x00, 0x00, 0x00, 0x00, 0x38, 0x00, 0x00, 0x00, 0x1f, 0x3d, 0xf8, 0xcb, 0x1f, + 0x52, 0x50, 0x41, 0x78, 0xc3, 0x4c, 0x3a, 0x76, 0x62, 0x23, 0x41, 0x6f, 0x85, 0xb2, 0x17, 0xda, 0xd2, 0x51, 0x41, 0x16, 0x9c, 0x45, 0x3d, 0x33, 0x55, 0x00, 0x3d, 0xc7, 0xac, 0x25, 0x3d, 0x00, + 0x00, 0x00, 0x00, 0x38, 0x00, 0x00, 0x00, 0x44, 0xe5, 0x5d, 0x83, 0x19, 0x93, 0x60, 0x3f, 0xf2, 0x70, 0xb0, 0x6b, 0xcf, 0xcd, 0x58, 0xbf, 0xa0, 0xee, 0x54, 0x82, 0xfd, 0xe1, 0x0c, 0xbf, 0x28, + 0x7c, 0xe1, 0x3a, 0xca, 0x65, 0xe9, 0x3a, 0xf8, 0xae, 0xdf, 0x3a, 0x30, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x80, 0x3f, 0x00, 0x00, 0x00, 0x00, 0x16, 0x15, 0x15, 0x10, 0x00, + 0x21, 0x15, 0x33, 0x0d, 0xdb, 0x0c, 0xcd, 0xd3, 0x01, 0x21, 0x43, 0x50, 0x00, 0x4d, 0x10, 0x93, 0xa2, 0x00, 0x00, 0x40, 0xa1, 0xa5, 0x32, 0x80, 0x00, 0x00, 0x00, 0x20, 0x00, 0x80, 0x00, 0x7f, + 0xdd, 0xfb, 0xa8, 0xa2, 0x22, 0xa9, 0xa5, 0xa9, 0x25, 0x24, 0xaa, 0x21, 0xaa, 0x29, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x6d, 0x39, 0xaa, 0xad, 0x7f, 0x4a, 0x28, 0x71, 0x1f, 0xd9, 0x2d, 0x00, + 0x8f, 0x17, 0x06, 0x7d, 0x6e, 0x01, 0xa8, 0x2d, 0xe1, 0x7c, 0x07, 0x8c, 0x1d, 0x5f, 0xf5, 0x41, 0x8b, 0x07, 0xfe, 0x0f, 0x50, 0x35, 0xdf, 0x85, 0x0a, 0x14, 0xb8, 0xad, 0xe6, 0x6a, 0x5a, 0x7e, + 0xa0, 0x41, 0xe2, 0xde, 0x76, 0x1c, 0xa0, 0x62, 0x70, 0x66, 0x16, 0x88, 0x1b, 0x9f, 0xce, 0xde, 0x14, 0xed, 0x6c, 0xbf, 0x60, 0x94, 0xf8, 0x0e, 0xdf, 0x6f, 0x44, 0xfe, 0x1c, 0x77, 0xb1, 0x3b, + 0x7c, 0x27, 0xa7, 0xb2, 0xe8, 0x6e, 0x8c, 0x2e, 0x34, 0x19, 0x63, 0x69, 0x4f, 0xff, 0xf7, 0xa0, 0x9e, 0x2c, 0xcf, 0xfd, 0x4c, 0x07, 0x8f, 0xa6, 0x57, 0x61, 0x75, 0x77, 0x84, 0x20, 0xe0, 0x09, + 0x5c, 0x3f, 0xff, 0xeb, 0x60, 0x4e, 0x05, 0x5f, 0xf8, 0x93, 0xaf, 0xa4, 0xe5, 0x28, 0x40, 0xa0, 0xa7, 0xa5, 0x52, 0xa0, 0x61, 0x07, 0x78, 0x00, 0x0f, 0x7f, 0xff, 0xf7, 0x50, 0x72, 0xa1, 0x50, + 0x18, 0xbe, 0x67, 0xff, 0xf8, 0x37, 0x9f, 0xfc, 0x7f, 0x5b, 0x15, 0xd8, 0x00, 0xe0, 0xca, 0x32, 0xdc, 0xcf, 0x31, 0xc4, 0x80, 0x04, 0xed, 0x41, 0x50, 0xb0, 0xa4, 0xd7, 0x32, 0x00, 0x00, 0x04, + 0xd3, 0x39, 0x00, 0x10, 0x33, 0x58, 0x00, 0x04, 0x47, 0xc2, 0x80, 0xbc, 0x2f, 0x0b, 0x82, 0x80, 0x94, 0x1f, 0x0b, 0x42, 0x40, 0x98, 0x2e, 0x0a, 0x82, 0x50, 0x50, 0x1c, 0x0b, 0x42, 0xa0, 0x44, + 0x28, 0x09, 0x43, 0x82, 0xe7, 0x0c, 0x80, 0x94, 0x41, 0x38, 0x39, 0x80, 0x73, 0xc1, 0x11, 0x6a, 0x2f, 0x34, 0x7d, 0x87, 0xa5, 0x9e, 0xe6, 0x1f, 0x88, 0x36, 0xaf, 0x6a, 0x88, 0x05, 0x10, 0x63, + 0xf4, 0x8c, 0x21, 0x57, 0x41, 0xc5, 0x1c, 0x8d, 0x36, 0xbd, 0x80, 0x91, 0xb2, 0x79, 0x73, 0x00, 0x7a, 0x6a, 0x08, 0xb9, 0xa0, 0x3d, 0xe0, 0x5b, 0x1d, 0x48, 0x92, 0x20, 0xe3, 0x57, 0xa1, 0x89, + 0x26, 0x9b, 0xfe, 0x4c, 0x18, 0xf4, 0x14, 0x2e, 0x2c, 0xc1, 0x6c, 0x23, 0xa7, 0x0b, 0x66, 0xfc, 0xc0, 0xc9, 0xcb, 0xa7, 0xc0, 0x18, 0x82, 0xd5, 0x59, 0x4a, 0xda, 0x6e, 0xa3, 0x6b, 0x06, 0xd5, + 0xa7, 0x00, 0xd5, 0xcd, 0xd3, 0xb8, 0x98, 0xbb, 0x37, 0x3c, 0x36, 0x6b, 0x13, 0x70, 0xf7, 0xd5, 0x46, 0x11, 0x00, 0x1e, 0xb1, 0x0d, 0x47, 0x1e, 0xcd, 0xdd, 0x8b, 0xb0, 0x40, 0xba, 0xb6, 0x86, + 0x5c, 0x4c, 0x25, 0x62, 0xdd, 0xff, 0xdb, 0xee, 0x6c, 0x98, 0xe5, 0xd4, 0xae, 0xf6, 0xb8, 0x5e, 0xf3, 0x3e, 0x9f, 0xa0, 0x6c, 0x1b, 0xbd, 0xec, 0xbb, 0xea, 0x88, 0x34, 0xf3, 0x57, 0x33, 0x9a, + 0x4a, 0x29, 0x70, 0x9f, 0x14, 0x99, 0x1d, 0x4f, 0x9e, 0xdd, 0x92, 0x48, 0x70, 0x24, 0x28, 0x5c, 0x1a, 0xb4, 0x65, 0x1c, 0x7d, 0x2f, 0x86, 0x31, 0xd3, 0x3f, 0xa6, 0xf6, 0xa0, 0x43, 0xb0, 0x0b, + 0x5f, 0xcc, 0xad, 0xb4, 0xa0, 0xe8, 0xd9, 0xe1, 0x60, 0x19, 0x46, 0xe7, 0xbd, 0x64, 0x2f, 0x09, 0x1a, 0x82, 0xb6, 0x1f, 0x37, 0x20, 0x79, 0xde, 0x64, 0x60, 0x4a, 0x9f, 0x2e, 0x52, 0x6d, 0xa0, + 0x20, 0x97, 0xab, 0xb6, 0xd2, 0x57, 0x44, 0xc7, 0xa4, 0xd1, 0x08, 0xf0, 0xd0, 0x3c, 0xe4, 0xc8, 0x9e, 0x75, 0x9a, 0x66, 0xea, 0xd8, 0x78, 0x24, 0x13, 0x7a, 0xd0, 0xd2, 0xab, 0x29, 0x1c, 0xaf, + 0x2e, 0x37, 0x94, 0x3b, 0x58, 0x31, 0x58, 0x56, 0xe1, 0x04, 0x45, 0x99, 0x7a, 0xc6, 0x7f, 0x85, 0xe1, 0x91, 0x9a, 0x77, 0x85, 0x5b, 0x6b, 0x3d, 0x2f, 0x55, 0x8c, 0x59, 0xe7, 0x06, 0x7f, 0x32, + 0xa4, 0x26, 0x44, 0xb7, 0x44, 0x10, 0x1d, 0xa5, 0xbb, 0xf4, 0x59, 0x00, 0xf6, 0x1b, 0x2a, 0x06, 0xc7, 0xb5, 0x62, 0x0a, 0x09, 0x3c, 0x00, 0xc1, 0x81, 0x00, 0x00, 0x1e, 0x00, 0x01, 0x00, 0x00, + 0x80, 0x00, 0x00, 0x4e, 0x66, 0x00, 0x00, 0x4f, 0x00, 0x0d, 0x1a, 0x02, 0x01, 0x01, 0x85, 0xbf, 0xff, 0x01, 0x00, 0x3e, 0x06, 0x07, 0x09, 0x08, 0x10, 0xff, 0x12, 0x13, 0x14, 0x15, 0x0e, 0x0a, + 0x0b, 0x0f, 0x44, 0x16, 0x39, 0x0e, 0x5a, 0x00, 0x00, 0x00, 0x00, 0xc0, 0x7b, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0xc3, 0x0d, 0xb5, 0x62, 0x0a, 0x09, 0x3c, 0x00, 0xc1, 0x81, 0x00, 0x00, 0x1e, + 0x00, 0x01, 0x00, 0x00, 0x80, 0x00, 0x00, 0x4e, 0x66, 0x00, 0x00, 0x4f, 0x00, 0x0d, 0x1a, 0x02, 0x01, 0x01, 0x85, 0xbf, 0xff, 0x01, 0x00, 0x3e, 0x06, 0x07, 0x09, 0x08, 0x10, 0xaa, 0x44, 0x13, + 0x28, 0xb6, 0x05, 0x83, 0x08, 0x5b, 0xdb, 0x68, 0x0c, 0x04, 0x3d, 0x83, 0x08, 0x32, 0xac, 0xe2, 0xed, 0x33, 0x6a, 0x09, 0x41, 0x00, 0xfe, 0x27, 0xf8, 0x04, 0x11, 0xd5, 0x09, 0xbc, 0x60, 0x60, + 0x00, 0x54, 0xfe, 0x61, 0x00, 0x94, 0x0d, 0x01, 0x00, 0xe0, 0x63, 0x08, 0x00, 0x9c, 0xf5, 0x02, 0x00, 0xea, 0xf1, 0x93, 0x8c, 0xd3, 0x00, 0x2e, 0x40, 0x90, 0x00, 0x0b, 0x4e, 0x55, 0x4c, 0x4c, + 0x41, 0x4e, 0x54, 0x45, 0x4e, 0x4e, 0x41, 0x00, 0x00, 0x15, 0x52, 0x54, 0x4b, 0x42, 0x61, 0x73, 0x65, 0x20, 0x55, 0x62, 0x6c, 0x6f, 0x78, 0x5f, 0x5a, 0x45, 0x44, 0x2d, 0x46, 0x39, 0x50, 0x05, + 0x32, 0x2e, 0x33, 0x2e, 0x30, 0x00, 0x7c, 0x92, 0xfb, 0x73, 0x04, 0x07, 0xe4, 0x01, 0x4c, 0xd0, 0x5b, 0x1e, 0x48, 0xfe, 0x92, 0xb2, 0xd6, 0xd1, 0xe6, 0x6f, 0x07, 0x30, 0x68, 0x18, 0x8e, 0x48, + 0xb3, 0xe1, 0x26, 0x20, 0x4a, 0x78, 0x47, 0x51, 0xdd, 0xe0, 0xdd, 0x5f, 0xb9, 0x68, 0xfc, 0x77, 0x81, 0x65, 0xb9, 0xfb, 0xcc, 0xb8, 0x7a, 0xe9, 0xf7, 0x42, 0x71, 0xa4, 0x02, 0xef, 0x4c, 0x2a, + 0x7e, 0x6d, 0xa0, 0xab, 0x4f, 0xc0, 0xc3, 0x47, 0xd2, 0x0b, 0x02, 0x13, 0xba, 0x38, 0x95, 0x3d, 0xcd, 0x3e, 0x2b, 0x92, 0x3f, 0x06, 0x3e, 0xab, 0xd5, 0x7a, 0x0c, 0xd7, 0x63, 0x17, 0x20, 0x1e, + 0xbe, 0xbb, 0x58, 0x29, 0xc5, 0xc0, 0xd1, 0x67, 0xec, 0xf7, 0x64, 0xf4, 0x9c, 0xf6, 0xc1, 0x45, 0xf5, 0xae, 0x5a, 0x80, 0xd0, 0xde, 0xeb, 0x73, 0x32, 0x1e, 0x7b, 0x1a, 0x58, 0x4a, 0xbb, 0x7d, + 0x5d, 0x54, 0xf3, 0xc7, 0x7d, 0xdd, 0xa9, 0xcd, 0x4d, 0x08, 0xf8, 0x16, 0x6d, 0xb6, 0x8a, 0x8e, 0xf5, 0x9f, 0xcc, 0x39, 0xb0, 0x8e, 0xa5, 0x77, 0x64, 0x44, 0x93, 0x37, 0x44, 0xc3, 0xc3, 0x5b, + 0x41, 0x29, 0x94, 0xde, 0x76, 0x57, 0x95, 0x5e, 0xcd, 0x16, 0x6d, 0x02, 0xa8, 0x18, 0x90, 0xf3, 0x7e, 0x69, 0x34, 0x3a, 0xc2, 0xc3, 0x94, 0x2a, 0xcb, 0x3a, 0x01, 0x43, 0x70, 0xc0, 0x52, 0x0a, + 0x00, 0xf2, 0x23, 0x67, 0x68, 0xde, 0x97, 0xf1, 0x3f, 0x8c, 0xbb, 0x19, 0x9f, 0x5b, 0xb4, 0x60, 0x67, 0xb7, 0x61, 0x61, 0x75, 0x33, 0x98, 0xff, 0xf0, 0xee, 0x64, 0x16, 0xcb, 0x29, 0xe8, 0x7f, + 0x1d, 0x95, 0x3a, 0xfc, 0xec, 0x34, 0xe3, 0x79, 0xf6, 0x11, 0x98, 0x39, 0x18, 0x35, 0xba, 0xed, 0x14, 0x80, 0x6b, 0x37, 0x43, 0xb4, 0x09, 0x8f, 0x78, 0xe8, 0x31, 0x98, 0x8d, 0x82, 0xf9, 0x0c, + 0xc8, 0xb9, 0x64, 0x9e, 0x6d, 0xd9, 0x50, 0x97, 0x94, 0x8e, 0x1a, 0xd7, 0xa2, 0x9d, 0x91, 0x36, 0xcd, 0x67, 0x19, 0xba, 0x32, 0xee, 0x29, 0x96, 0x02, 0x03, 0x87, 0xe7, 0x71, 0xea, 0xff, 0xe2, + 0x93, 0x48, 0x32, 0xa6, 0x3b, 0x73, 0x60, 0x3c, 0xa1, 0x81, 0xc7, 0xaa, 0x2d, 0x1f, 0x2e, 0x5a, 0x43, 0x11, 0x6f, 0x14, 0x1c, 0x6f, 0x9e, 0x04, 0xd4, 0x6b, 0xd3, 0xe9, 0x0d, 0xb5, 0x62, 0x0a, + 0x0b, 0x1c, 0x00, 0x0c, 0x9e, 0x0c, 0x91, 0x00, 0x8a, 0xa9, 0xb8, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x57, + 0x8e, 0x73, 0x02, 0x58, 0xea, 0x18, 0xb9, 0xa1, 0x8f, 0xc0, 0x5b, 0x19, 0x88, 0xda, 0x72, 0xd2, 0x47, 0xb4, 0xf6, 0x0b, 0x58, 0x9a, 0x57, 0x9e, 0x28, 0xb3, 0x29, 0x13, 0xdd, 0xad, 0x03, 0x18, + 0x80, 0xbe, 0xdf, 0xcd, 0x67, 0xf9, 0xae, 0x17, 0xbe, 0x9c, 0x53, 0x38, 0xed, 0x41, 0xf0, 0xc2, 0xd7, 0xca, 0x77, 0x31, 0x3d, 0xad, 0xa2, 0xb5, 0x18, 0x53, 0x64, 0xa4, 0xc1, 0xf0, 0x16, 0x53, + 0xa5, 0x1e, 0x76, 0xa9, 0x37, 0x97, 0x52, 0x54, 0x47, 0xed, 0x41, 0x73, 0xe1, 0x70, 0x63, 0x89, 0x30, 0x29, 0x77, 0x1a, 0x39, 0x9d, 0x01, 0xb2, 0x02, 0x65, 0x6f, 0x4b, 0x75, 0x6f, 0x01, 0x01, + 0xf0, 0x21, 0x5a, 0x4e, 0xc6, 0x2d, 0x2a, 0xa3, 0x9f, 0x3a, 0x08, 0x03, 0x93, 0x2d, 0x1e, 0x82, 0x94, 0xe9, 0x67, 0xb3, 0xdb, 0xd7, 0x7e, 0xbd, 0x49, 0x5a, 0x46, 0xe5, 0x03, 0xe8, 0x9e, 0x7a, + 0xee, 0xba, 0x78, 0x6c, 0x12, 0x71, 0xb1, 0xf7, 0xc7, 0xfb, 0xc5, 0x65, 0xa7, 0xa8, 0x83, 0xf8, 0xb9, 0x9b, 0x83, 0x08, 0x29, 0xe6, 0x84, 0xf5, 0x6f, 0x8d, 0xb2, 0x01, 0x74, 0xed, 0x27, 0xc7, + 0x57, 0xc9, 0x41, 0x63, 0x8e, 0xb5, 0x7c, 0x6f, 0xfa, 0x1f, 0xfa, 0xee, 0xfc, 0x17, 0xf9, 0x9b, 0x60, 0xa4, 0x16, 0x6c, 0xa1, 0x3e, 0xb7, 0xe2, 0x16, 0xc6, 0xd7, 0x24, 0xd2, 0x06, 0xc6, 0x9a, + 0xb2, 0xb5, 0x62, 0x01, 0x36, 0x40, 0x00, 0xb8, 0xfa, 0x43, 0x13, 0x00, 0x01, 0x01, 0x00, 0x32, 0x30, 0x19, 0x40, 0x00, 0x00, 0x80, 0x3f, 0x2e, 0x8e, 0x69, 0x38, 0x88, 0x21, 0xad, 0xb6, 0x08, + 0xd0, 0xf5, 0x37, 0x6d, 0x9e, 0x00, 0x38, 0x3b, 0xf0, 0xc3, 0xb5, 0x96, 0x61, 0x52, 0x39, 0xa9, 0x3c, 0x91, 0x3b, 0x58, 0x71, 0xe4, 0xb8, 0xb0, 0xc8, 0xb1, 0x39, 0x32, 0xfd, 0x05, 0x3b, 0x3c, + 0xb1, 0x01, 0xb9, 0x3a, 0xe5, 0x8f, 0x3b, 0x47, 0x29, 0x66, 0x21, 0xd1, 0x07, 0x5c, 0x00, 0x00, 0x00, 0x01, 0x03, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x0a, 0x00, 0x00, 0x00, 0x14, 0x00, 0x00, + 0x00, 0xe2, 0xff, 0xff, 0xff, 0x01, 0x01, 0x01, 0x01, 0x01, 0x00, 0x00, 0x00, 0x00, 0x01, 0x0a, 0x00, 0x4e, 0x61, 0xbc, 0x00, 0x0b, 0x00, 0x00, 0x00, 0x15, 0x00, 0x00, 0x00, 0xe3, 0xff, 0xff, + 0xff, 0x01, 0x01, 0x01, 0x01, 0x02, 0x00, 0x00, 0x00, 0x00, 0x01, 0x0a, 0x00, 0x4e, 0x61, 0xbc, 0x00, 0x0c, 0x00, 0x00, 0x00, 0x16, 0x00, 0x00, 0x00, 0xe4, 0xff, 0xff, 0xff, 0x01, 0x01, 0x01, + 0x01, 0x03, 0x00, 0x00, 0x00, 0x00, 0x01, 0x0a, 0x00, 0x4e, 0x61, 0xbc, 0x00, 0x26, 0x54, 0xaa, 0x34, 0xb5, 0x62, 0x01, 0x35, 0x84, 0x02, 0xb8, 0xfa, 0x43, 0x13, 0x01, 0x35, 0x00, 0x00, 0x00, + 0x01, 0x27, 0x07, 0x00, 0x01, 0xf2, 0xff, 0x17, 0x19, 0x00, 0x00, 0x00, 0x07, 0x1a, 0x04, 0x1c, 0x01, 0x00, 0x00, 0x17, 0x19, 0x00, 0x00, 0x00, 0x08, 0x2e, 0x3e, 0x2e, 0x01, 0x02, 0x00, 0x5f, + 0x19, 0x32, 0x00, 0x00, 0x0a, 0x31, 0x40, 0x5f, 0x00, 0x05, 0x00, 0x5f, 0x19, 0x32, 0x00, 0x00, 0x0f, 0x00, 0x02, 0x18, 0x00, 0x00, 0x00, 0x11, 0x1a, 0x00, 0x00, 0x00, 0x10, 0x29, 0x23, 0xc1, + 0x00, 0xfa, 0xff, 0x5f, 0x19, 0x32, 0x00, 0x00, 0x12, 0x29, 0x0a, 0x46, 0x00, 0xec, 0xff, 0x17, 0x19, 0x00, 0x00, 0x00, 0x15, 0x2b, 0x21, 0x09, 0x01, 0xfd, 0xff, 0x5f, 0x19, 0x32, 0x00, 0x00, + 0x17, 0x2c, 0x25, 0x35, 0x00, 0xfa, 0xff, 0x5f, 0x19, 0x32, 0x00, 0x00, 0x1a, 0x09, 0x05, 0xaf, 0x00, 0x00, 0x00, 0x13, 0x19, 0x00, 0x00, 0x00, 0x1b, 0x2f, 0x50, 0x78, 0x00, 0x02, 0x00, 0x5f, + 0x19, 0x32, 0x00, 0x00, 0x1e, 0x26, 0x04, 0x3e, 0x01, 0x00, 0x00, 0x17, 0x1a, 0x00, 0x00, 0x00, 0x20, 0x27, 0x0a, 0x83, 0x00, 0x00, 0x00, 0x5f, 0x19, 0x32, 0x00, 0x01, 0x7b, 0x27, 0x1f, 0x96, + 0x00, 0x00, 0x00, 0x17, 0x1a, 0x00, 0x00, 0x01, 0x7f, 0x1f, 0x14, 0x7d, 0x00, 0x00, 0x00, 0x07, 0x1a, 0x00, 0x00, 0x01, 0x80, 0x00, 0x02, 0x66, 0x00, 0x00, 0x00, 0x00, 0x12, 0x00, 0x00, 0x01, + 0x88, 0x29, 0x23, 0xb9, 0x00, 0x00, 0x00, 0x17, 0x1a, 0x00, 0x00, 0x02, 0x01, 0x2c, 0x2f, 0xec, 0x00, 0x05, 0x00, 0x5f, 0x19, 0x32, 0x00, 0x02, 0x03, 0x25, 0x07, 0x1b, 0x00, 0x00, 0x00, 0x17, + 0x19, 0x00, 0x00, 0x02, 0x07, 0x26, 0x10, 0x7f, 0x00, 0xe1, 0xff, 0x1f, 0x19, 0x00, 0x00, 0x02, 0x08, 0x29, 0x17, 0x49, 0x00, 0xff, 0xff, 0x5f, 0x19, 0x32, 0x00, 0x02, 0x0d, 0x2a, 0x27, 0x43, + 0x00, 0x0b, 0x00, 0x5f, 0x19, 0x32, 0x00, 0x02, 0x15, 0x26, 0x14, 0xbb, 0x00, 0xfb, 0xff, 0x5f, 0x19, 0x32, 0x00, 0x02, 0x1a, 0x2d, 0x4d, 0x39, 0x01, 0x02, 0x00, 0x5f, 0x19, 0x32, 0x00, 0x02, + 0x1f, 0x2a, 0x1e, 0x35, 0x01, 0x07, 0x00, 0x5f, 0x19, 0x32, 0x00, 0x02, 0x21, 0x28, 0x1e, 0x08, 0x01, 0x01, 0x00, 0x5f, 0x19, 0x32, 0x00, 0x03, 0x02, 0x00, 0x02, 0x64, 0x00, 0x00, 0x00, 0x10, + 0x12, 0x00, 0x00, 0x03, 0x05, 0x00, 0x12, 0x78, 0x00, 0x00, 0x00, 0x10, 0x12, 0x00, 0x00, 0x03, 0x08, 0x20, 0x03, 0x2e, 0x00, 0x00, 0x00, 0x17, 0x1a, 0x00, 0x00, 0x03, 0x0d, 0x25, 0x0e, 0x31, + 0x00, 0x07, 0x00, 0x5f, 0x19, 0x32, 0x00, 0x03, 0x13, 0x00, 0x07, 0xb6, 0x00, 0x00, 0x00, 0x10, 0x12, 0x00, 0x00, 0x03, 0x14, 0x2d, 0x28, 0x8f, 0x00, 0xf7, 0xff, 0x1f, 0x19, 0x00, 0x00, 0x03, + 0x18, 0x00, 0x01, 0x55, 0x01, 0x00, 0x00, 0x10, 0x12, 0x00, 0x00, 0x03, 0x1a, 0x00, 0x13, 0x2c, 0x01, 0x00, 0x00, 0x10, 0x12, 0x00, 0x00, 0x03, 0x1d, 0x2f, 0x4c, 0x3f, 0x01, 0x03, 0x00, 0x5f, + 0x19, 0x32, 0x00, 0x03, 0x1e, 0x2d, 0x2a, 0x60, 0x00, 0xfd, 0xff, 0x5f, 0x19, 0x32, 0x00, 0x03, 0x20, 0x2d, 0x27, 0x43, 0x00, 0x04, 0x00, 0x5f, 0x19, 0x32, 0x00, 0x03, 0x23, 0x27, 0x16, 0x20, + 0x01, 0x00, 0x00, 0x27, 0x1a, 0x00, 0x00, 0x03, 0x27, 0x00, 0x03, 0x43, 0x00, 0x00, 0x00, 0x10, 0x12, 0x00, 0x00, 0x03, 0x29, 0x00, 0x04, 0x1c, 0x00, 0x00, 0x00, 0x10, 0x19, 0x00, 0x00, 0x03, + 0x2d, 0x28, 0x14, 0xf5, 0x00, 0xf9, 0xff, 0x1f, 0x19, 0x00, 0x00, 0x03, 0x3c, 0x00, 0x04, 0x67, 0x00, 0x00, 0x00, 0x10, 0x12, 0x00, 0x00, 0x05, 0x03, 0x00, 0xa5, 0x00, 0x00, 0x00, 0x00, 0x01, + 0x00, 0x00, 0x00, 0x06, 0x01, 0x26, 0x15, 0x99, 0x00, 0xea, 0xff, 0x5f, 0x19, 0x32, 0x00, 0x06, 0x07, 0x2b, 0x1b, 0x24, 0x00, 0xf6, 0xff, 0x5f, 0x19, 0x32, 0x00, 0x06, 0x08, 0x2d, 0x2c, 0x5f, + 0x00, 0xeb, 0xff, 0x5f, 0x19, 0x32, 0x00, 0x06, 0x0d, 0x1c, 0x0b, 0xd4, 0x00, 0xe1, 0xff, 0x5f, 0x19, 0x12, 0x00, 0x06, 0x0e +}; diff --git a/fpsdk_common/test/data/test_data_nmea.bin b/fpsdk_common/test/data/test_data_nmea.bin new file mode 100644 index 0000000..e1cc468 --- /dev/null +++ b/fpsdk_common/test/data/test_data_nmea.bin @@ -0,0 +1,2 @@ +$GNRMC,174644.20,A,4724.01818,N,00827.02244,E,0.013,,150323,,,R,V*0D +$GNGGA,174644.20,4724.01818,N,00827.02244,E,4,12,0.58,412.1,M,47.3,M,1.2,0000*6C diff --git a/fpsdk_common/test/data/test_data_nmea.cpp b/fpsdk_common/test/data/test_data_nmea.cpp new file mode 100644 index 0000000..c6343d3 --- /dev/null +++ b/fpsdk_common/test/data/test_data_nmea.cpp @@ -0,0 +1,8 @@ +// clang-format off +static const std::vector TEST_DATA_NMEA_BIN = { + 0x24, 0x47, 0x4e, 0x52, 0x4d, 0x43, 0x2c, 0x31, 0x37, 0x34, 0x36, 0x34, 0x34, 0x2e, 0x32, 0x30, 0x2c, 0x41, 0x2c, 0x34, 0x37, 0x32, 0x34, 0x2e, 0x30, 0x31, 0x38, 0x31, 0x38, 0x2c, 0x4e, 0x2c, + 0x30, 0x30, 0x38, 0x32, 0x37, 0x2e, 0x30, 0x32, 0x32, 0x34, 0x34, 0x2c, 0x45, 0x2c, 0x30, 0x2e, 0x30, 0x31, 0x33, 0x2c, 0x2c, 0x31, 0x35, 0x30, 0x33, 0x32, 0x33, 0x2c, 0x2c, 0x2c, 0x52, 0x2c, + 0x56, 0x2a, 0x30, 0x44, 0x0d, 0x0a, 0x24, 0x47, 0x4e, 0x47, 0x47, 0x41, 0x2c, 0x31, 0x37, 0x34, 0x36, 0x34, 0x34, 0x2e, 0x32, 0x30, 0x2c, 0x34, 0x37, 0x32, 0x34, 0x2e, 0x30, 0x31, 0x38, 0x31, + 0x38, 0x2c, 0x4e, 0x2c, 0x30, 0x30, 0x38, 0x32, 0x37, 0x2e, 0x30, 0x32, 0x32, 0x34, 0x34, 0x2c, 0x45, 0x2c, 0x34, 0x2c, 0x31, 0x32, 0x2c, 0x30, 0x2e, 0x35, 0x38, 0x2c, 0x34, 0x31, 0x32, 0x2e, + 0x31, 0x2c, 0x4d, 0x2c, 0x34, 0x37, 0x2e, 0x33, 0x2c, 0x4d, 0x2c, 0x31, 0x2e, 0x32, 0x2c, 0x30, 0x30, 0x30, 0x30, 0x2a, 0x36, 0x43, 0x0d, 0x0a +}; diff --git a/fpsdk_common/test/data/test_data_novb.bin b/fpsdk_common/test/data/test_data_novb.bin new file mode 100644 index 0000000..7fe6c85 Binary files /dev/null and b/fpsdk_common/test/data/test_data_novb.bin differ diff --git a/fpsdk_common/test/data/test_data_novb.cpp b/fpsdk_common/test/data/test_data_novb.cpp new file mode 100644 index 0000000..1c697d6 --- /dev/null +++ b/fpsdk_common/test/data/test_data_novb.cpp @@ -0,0 +1,13 @@ +// clang-format off +static const std::vector TEST_DATA_NOVB_BIN = { + 0xaa, 0x44, 0x12, 0x1c, 0x2a, 0x00, 0x00, 0xa0, 0x48, 0x00, 0x00, 0x00, 0x23, 0xb4, 0x83, 0x08, 0x64, 0xdb, 0x68, 0x0c, 0x00, 0x08, 0x00, 0x03, 0xba, 0xcd, 0x19, 0x40, 0x00, 0x00, 0x00, 0x00, + 0x38, 0x00, 0x00, 0x00, 0xcf, 0x6a, 0x48, 0x15, 0x4c, 0xb3, 0x47, 0x40, 0xe6, 0xeb, 0x19, 0x6b, 0xb8, 0xe3, 0x20, 0x40, 0x00, 0x00, 0x58, 0x31, 0xd2, 0x84, 0x78, 0x40, 0x66, 0x66, 0x3e, 0x42, + 0x3d, 0x00, 0x00, 0x00, 0x85, 0x2d, 0x11, 0x3d, 0xf3, 0xd6, 0x04, 0x3d, 0xc6, 0x57, 0x52, 0x3d, 0x30, 0x00, 0x00, 0x00, 0x00, 0x00, 0x80, 0x3f, 0x00, 0x00, 0x00, 0x00, 0x16, 0x15, 0x15, 0x10, + 0x00, 0x21, 0x15, 0x33, 0x3f, 0x6c, 0xbc, 0xfe, 0xaa, 0x44, 0x12, 0x1c, 0xf1, 0x00, 0x00, 0xa0, 0x70, 0x00, 0x00, 0x00, 0x23, 0xb4, 0x83, 0x08, 0x64, 0xdb, 0x68, 0x0c, 0x00, 0x08, 0x00, 0x03, + 0xcf, 0x44, 0x19, 0x40, 0x00, 0x00, 0x00, 0x00, 0x38, 0x00, 0x00, 0x00, 0x1f, 0x3d, 0xf8, 0xcb, 0x1f, 0x52, 0x50, 0x41, 0x78, 0xc3, 0x4c, 0x3a, 0x76, 0x62, 0x23, 0x41, 0x6f, 0x85, 0xb2, 0x17, + 0xda, 0xd2, 0x51, 0x41, 0x16, 0x9c, 0x45, 0x3d, 0x33, 0x55, 0x00, 0x3d, 0xc7, 0xac, 0x25, 0x3d, 0x00, 0x00, 0x00, 0x00, 0x38, 0x00, 0x00, 0x00, 0x44, 0xe5, 0x5d, 0x83, 0x19, 0x93, 0x60, 0x3f, + 0xf2, 0x70, 0xb0, 0x6b, 0xcf, 0xcd, 0x58, 0xbf, 0xa0, 0xee, 0x54, 0x82, 0xfd, 0xe1, 0x0c, 0xbf, 0x28, 0x7c, 0xe1, 0x3a, 0xca, 0x65, 0xe9, 0x3a, 0xf8, 0xae, 0xdf, 0x3a, 0x30, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x80, 0x3f, 0x00, 0x00, 0x00, 0x00, 0x16, 0x15, 0x15, 0x10, 0x00, 0x21, 0x15, 0x33, 0x0d, 0xdb, 0x0c, 0xcd, 0xaa, 0x44, 0x13, 0x28, 0xb6, 0x05, 0x83, 0x08, + 0x5b, 0xdb, 0x68, 0x0c, 0x04, 0x3d, 0x83, 0x08, 0x32, 0xac, 0xe2, 0xed, 0x33, 0x6a, 0x09, 0x41, 0x00, 0xfe, 0x27, 0xf8, 0x04, 0x11, 0xd5, 0x09, 0xbc, 0x60, 0x60, 0x00, 0x54, 0xfe, 0x61, 0x00, + 0x94, 0x0d, 0x01, 0x00, 0xe0, 0x63, 0x08, 0x00, 0x9c, 0xf5, 0x02, 0x00, 0xea, 0xf1, 0x93, 0x8c +}; diff --git a/fpsdk_common/test/data/test_data_rtcm3.bin b/fpsdk_common/test/data/test_data_rtcm3.bin new file mode 100644 index 0000000..1147dfa Binary files /dev/null and b/fpsdk_common/test/data/test_data_rtcm3.bin differ diff --git a/fpsdk_common/test/data/test_data_rtcm3.cpp b/fpsdk_common/test/data/test_data_rtcm3.cpp new file mode 100644 index 0000000..ac53d21 --- /dev/null +++ b/fpsdk_common/test/data/test_data_rtcm3.cpp @@ -0,0 +1,15 @@ +// clang-format off +static const std::vector TEST_DATA_RTCM3_BIN = { + 0xd3, 0x00, 0x16, 0x45, 0x30, 0x00, 0x4d, 0x10, 0x93, 0xa2, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x1f, 0x9b, 0x2f, 0xd3, 0x01, 0x21, 0x43, + 0x50, 0x00, 0x4d, 0x10, 0x93, 0xa2, 0x00, 0x00, 0x40, 0xa1, 0xa5, 0x32, 0x80, 0x00, 0x00, 0x00, 0x20, 0x00, 0x80, 0x00, 0x7f, 0xdd, 0xfb, 0xa8, 0xa2, 0x22, 0xa9, 0xa5, 0xa9, 0x25, 0x24, 0xaa, + 0x21, 0xaa, 0x29, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x6d, 0x39, 0xaa, 0xad, 0x7f, 0x4a, 0x28, 0x71, 0x1f, 0xd9, 0x2d, 0x00, 0x8f, 0x17, 0x06, 0x7d, 0x6e, 0x01, 0xa8, 0x2d, 0xe1, 0x7c, 0x07, + 0x8c, 0x1d, 0x5f, 0xf5, 0x41, 0x8b, 0x07, 0xfe, 0x0f, 0x50, 0x35, 0xdf, 0x85, 0x0a, 0x14, 0xb8, 0xad, 0xe6, 0x6a, 0x5a, 0x7e, 0xa0, 0x41, 0xe2, 0xde, 0x76, 0x1c, 0xa0, 0x62, 0x70, 0x66, 0x16, + 0x88, 0x1b, 0x9f, 0xce, 0xde, 0x14, 0xed, 0x6c, 0xbf, 0x60, 0x94, 0xf8, 0x0e, 0xdf, 0x6f, 0x44, 0xfe, 0x1c, 0x77, 0xb1, 0x3b, 0x7c, 0x27, 0xa7, 0xb2, 0xe8, 0x6e, 0x8c, 0x2e, 0x34, 0x19, 0x63, + 0x69, 0x4f, 0xff, 0xf7, 0xa0, 0x9e, 0x2c, 0xcf, 0xfd, 0x4c, 0x07, 0x8f, 0xa6, 0x57, 0x61, 0x75, 0x77, 0x84, 0x20, 0xe0, 0x09, 0x5c, 0x3f, 0xff, 0xeb, 0x60, 0x4e, 0x05, 0x5f, 0xf8, 0x93, 0xaf, + 0xa4, 0xe5, 0x28, 0x40, 0xa0, 0xa7, 0xa5, 0x52, 0xa0, 0x61, 0x07, 0x78, 0x00, 0x0f, 0x7f, 0xff, 0xf7, 0x50, 0x72, 0xa1, 0x50, 0x18, 0xbe, 0x67, 0xff, 0xf8, 0x37, 0x9f, 0xfc, 0x7f, 0x5b, 0x15, + 0xd8, 0x00, 0xe0, 0xca, 0x32, 0xdc, 0xcf, 0x31, 0xc4, 0x80, 0x04, 0xed, 0x41, 0x50, 0xb0, 0xa4, 0xd7, 0x32, 0x00, 0x00, 0x04, 0xd3, 0x39, 0x00, 0x10, 0x33, 0x58, 0x00, 0x04, 0x47, 0xc2, 0x80, + 0xbc, 0x2f, 0x0b, 0x82, 0x80, 0x94, 0x1f, 0x0b, 0x42, 0x40, 0x98, 0x2e, 0x0a, 0x82, 0x50, 0x50, 0x1c, 0x0b, 0x42, 0xa0, 0x44, 0x28, 0x09, 0x43, 0x82, 0xe7, 0x0c, 0x80, 0x94, 0x41, 0x38, 0x39, + 0x80, 0x73, 0xc1, 0x11, 0x6a, 0x2f, 0x34, 0x7d, 0x87, 0xa5, 0x9e, 0xe6, 0x1f, 0x88, 0x36, 0xaf, 0x6a, 0x88, 0x05, 0x10, 0x63, 0xf4, 0x8c, 0x21, 0x57, 0x41, 0xc5, 0x1c, 0x8d, 0x36, 0xbd, 0x80, + 0x91, 0xb2, 0x79, 0xd3, 0x00, 0x2e, 0x40, 0x90, 0x00, 0x0b, 0x4e, 0x55, 0x4c, 0x4c, 0x41, 0x4e, 0x54, 0x45, 0x4e, 0x4e, 0x41, 0x00, 0x00, 0x15, 0x52, 0x54, 0x4b, 0x42, 0x61, 0x73, 0x65, 0x20, + 0x55, 0x62, 0x6c, 0x6f, 0x78, 0x5f, 0x5a, 0x45, 0x44, 0x2d, 0x46, 0x39, 0x50, 0x05, 0x32, 0x2e, 0x33, 0x2e, 0x30, 0x00, 0x7c, 0x92, 0xfb +}; diff --git a/fpsdk_common/test/data/test_data_spartn.bin b/fpsdk_common/test/data/test_data_spartn.bin new file mode 100644 index 0000000..b430238 Binary files /dev/null and b/fpsdk_common/test/data/test_data_spartn.bin differ diff --git a/fpsdk_common/test/data/test_data_spartn.cpp b/fpsdk_common/test/data/test_data_spartn.cpp new file mode 100644 index 0000000..d5ace07 --- /dev/null +++ b/fpsdk_common/test/data/test_data_spartn.cpp @@ -0,0 +1,20 @@ +// clang-format off +static const std::vector TEST_DATA_SPARTN_BIN = { + 0x73, 0x00, 0x10, 0xe3, 0x18, 0xb9, 0xa1, 0x8d, 0x68, 0x5b, 0x1f, 0x88, 0xa0, 0xba, 0xc2, 0x37, 0x43, 0xeb, 0x3f, 0xbe, 0x08, 0xf8, 0x51, 0x7f, 0x3a, 0x9a, 0x78, 0x32, 0x85, 0xc6, 0xe2, 0xd0, + 0x7e, 0xee, 0x37, 0xcb, 0x3d, 0x6a, 0x8f, 0xf1, 0x4c, 0x27, 0x43, 0x0d, 0x2a, 0x70, 0xf2, 0x01, 0x73, 0x00, 0x7a, 0x6a, 0x08, 0xb9, 0xa0, 0x3d, 0xe0, 0x5b, 0x1d, 0x48, 0x92, 0x20, 0xe3, 0x57, + 0xa1, 0x89, 0x26, 0x9b, 0xfe, 0x4c, 0x18, 0xf4, 0x14, 0x2e, 0x2c, 0xc1, 0x6c, 0x23, 0xa7, 0x0b, 0x66, 0xfc, 0xc0, 0xc9, 0xcb, 0xa7, 0xc0, 0x18, 0x82, 0xd5, 0x59, 0x4a, 0xda, 0x6e, 0xa3, 0x6b, + 0x06, 0xd5, 0xa7, 0x00, 0xd5, 0xcd, 0xd3, 0xb8, 0x98, 0xbb, 0x37, 0x3c, 0x36, 0x6b, 0x13, 0x70, 0xf7, 0xd5, 0x46, 0x11, 0x00, 0x1e, 0xb1, 0x0d, 0x47, 0x1e, 0xcd, 0xdd, 0x8b, 0xb0, 0x40, 0xba, + 0xb6, 0x86, 0x5c, 0x4c, 0x25, 0x62, 0xdd, 0xff, 0xdb, 0xee, 0x6c, 0x98, 0xe5, 0xd4, 0xae, 0xf6, 0xb8, 0x5e, 0xf3, 0x3e, 0x9f, 0xa0, 0x6c, 0x1b, 0xbd, 0xec, 0xbb, 0xea, 0x88, 0x34, 0xf3, 0x57, + 0x33, 0x9a, 0x4a, 0x29, 0x70, 0x9f, 0x14, 0x99, 0x1d, 0x4f, 0x9e, 0xdd, 0x92, 0x48, 0x70, 0x24, 0x28, 0x5c, 0x1a, 0xb4, 0x65, 0x1c, 0x7d, 0x2f, 0x86, 0x31, 0xd3, 0x3f, 0xa6, 0xf6, 0xa0, 0x43, + 0xb0, 0x0b, 0x5f, 0xcc, 0xad, 0xb4, 0xa0, 0xe8, 0xd9, 0xe1, 0x60, 0x19, 0x46, 0xe7, 0xbd, 0x64, 0x2f, 0x09, 0x1a, 0x82, 0xb6, 0x1f, 0x37, 0x20, 0x79, 0xde, 0x64, 0x60, 0x4a, 0x9f, 0x2e, 0x52, + 0x6d, 0xa0, 0x20, 0x97, 0xab, 0xb6, 0xd2, 0x57, 0x44, 0xc7, 0xa4, 0xd1, 0x08, 0xf0, 0xd0, 0x3c, 0xe4, 0xc8, 0x9e, 0x75, 0x9a, 0x66, 0xea, 0xd8, 0x78, 0x24, 0x13, 0x7a, 0xd0, 0xd2, 0xab, 0x29, + 0x1c, 0xaf, 0x2e, 0x37, 0x94, 0x3b, 0x58, 0x31, 0x58, 0x56, 0xe1, 0x04, 0x45, 0x99, 0x7a, 0xc6, 0x7f, 0x85, 0xe1, 0x91, 0x9a, 0x77, 0x85, 0x5b, 0x6b, 0x3d, 0x2f, 0x55, 0x8c, 0x59, 0xe7, 0x06, + 0x7f, 0x32, 0xa4, 0x26, 0x44, 0xb7, 0x44, 0x10, 0x1d, 0xa5, 0xbb, 0xf4, 0x59, 0x00, 0xf6, 0x1b, 0x2a, 0x06, 0xc7, 0x73, 0x04, 0x07, 0xe4, 0x01, 0x4c, 0xd0, 0x5b, 0x1e, 0x48, 0xfe, 0x92, 0xb2, + 0xd6, 0xd1, 0xe6, 0x6f, 0x07, 0x30, 0x68, 0x18, 0x8e, 0x48, 0xb3, 0xe1, 0x26, 0x20, 0x4a, 0x73, 0x02, 0x58, 0xea, 0x18, 0xb9, 0xa1, 0x8f, 0xc0, 0x5b, 0x19, 0x88, 0xda, 0x72, 0xd2, 0x47, 0xb4, + 0xf6, 0x0b, 0x58, 0x9a, 0x57, 0x9e, 0x28, 0xb3, 0x29, 0x13, 0xdd, 0xad, 0x03, 0x18, 0x80, 0xbe, 0xdf, 0xcd, 0x67, 0xf9, 0xae, 0x17, 0xbe, 0x9c, 0x53, 0x38, 0xed, 0x41, 0xf0, 0xc2, 0xd7, 0xca, + 0x77, 0x31, 0x3d, 0xad, 0xa2, 0xb5, 0x18, 0x53, 0x64, 0xa4, 0xc1, 0xf0, 0x16, 0x53, 0xa5, 0x1e, 0x76, 0xa9, 0x37, 0x97, 0x52, 0x54, 0x47, 0xed, 0x41, 0x73, 0xe1, 0x70, 0x63, 0x89, 0x30, 0x29, + 0x77, 0x1a, 0x39, 0x9d, 0x01, 0xb2, 0x02, 0x65, 0x6f, 0x4b, 0x75, 0x6f, 0x01, 0x01, 0xf0, 0x21, 0x5a, 0x4e, 0xc6, 0x2d, 0x2a, 0xa3, 0x9f, 0x3a, 0x08, 0x03, 0x93, 0x2d, 0x1e, 0x82, 0x94, 0xe9, + 0x67, 0xb3, 0xdb, 0xd7, 0x7e, 0xbd, 0x49, 0x5a, 0x46, 0xe5, 0x03, 0xe8, 0x9e, 0x7a, 0xee, 0xba, 0x78, 0x6c, 0x12, 0x71, 0xb1, 0xf7, 0xc7, 0xfb, 0xc5, 0x65, 0xa7, 0xa8, 0x83, 0xf8, 0xb9, 0x9b, + 0x83, 0x08, 0x29, 0xe6, 0x84, 0xf5, 0x6f, 0x8d, 0xb2, 0x01, 0x74, 0xed, 0x27, 0xc7, 0x57, 0xc9, 0x41, 0x63, 0x8e, 0xb5, 0x7c, 0x6f, 0xfa, 0x1f, 0xfa, 0xee, 0xfc, 0x17, 0xf9, 0x9b, 0x60, 0xa4, + 0x16, 0x6c, 0xa1, 0x3e, 0xb7, 0xe2, 0x16, 0xc6, 0xd7, 0x24, 0xd2, 0x06, 0xc6, 0x9a, 0xb2 +}; diff --git a/fpsdk_common/test/data/test_data_ubx.bin b/fpsdk_common/test/data/test_data_ubx.bin new file mode 100644 index 0000000..95624c5 Binary files /dev/null and b/fpsdk_common/test/data/test_data_ubx.bin differ diff --git a/fpsdk_common/test/data/test_data_ubx.cpp b/fpsdk_common/test/data/test_data_ubx.cpp new file mode 100644 index 0000000..5337123 --- /dev/null +++ b/fpsdk_common/test/data/test_data_ubx.cpp @@ -0,0 +1,208 @@ +// clang-format off +static const std::vector TEST_DATA_UBX_BIN = { + 0xb5, 0x62, 0x0d, 0x01, 0x10, 0x00, 0x88, 0xb7, 0x43, 0x13, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0xcd, 0x08, 0x1b, 0x3f, 0xe2, 0xd2, 0xb5, 0x62, 0x0a, 0x09, 0x3c, 0x00, 0xc1, 0x81, + 0x00, 0x00, 0x1e, 0x00, 0x01, 0x00, 0x00, 0x80, 0x00, 0x00, 0x4e, 0x66, 0x00, 0x00, 0x4f, 0x00, 0x0d, 0x1a, 0x02, 0x01, 0x01, 0x85, 0xbf, 0xff, 0x01, 0x00, 0x3e, 0x06, 0x07, 0x09, 0x08, 0x10, + 0xff, 0x12, 0x13, 0x14, 0x15, 0x0e, 0x0a, 0x0b, 0x0f, 0x44, 0x16, 0x39, 0x0e, 0x5a, 0x00, 0x00, 0x00, 0x00, 0xc0, 0x7b, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0xc3, 0x0d, 0xb5, 0x62, 0x0a, 0x0b, + 0x1c, 0x00, 0x0c, 0x9e, 0x0c, 0x91, 0x00, 0x8a, 0xa9, 0xb8, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x57, 0x8e, + 0xb5, 0x62, 0x0a, 0x0e, 0x0c, 0x00, 0x00, 0x00, 0x00, 0x00, 0x2f, 0x00, 0x01, 0x00, 0x00, 0x00, 0x00, 0x00, 0x54, 0x98, 0xb5, 0x62, 0x02, 0x13, 0x30, 0x00, 0x00, 0x1b, 0x04, 0x00, 0x0a, 0x52, + 0x02, 0x43, 0x93, 0xe6, 0x6d, 0x8b, 0xf8, 0x68, 0xb0, 0x71, 0x84, 0x18, 0x15, 0x64, 0x00, 0xb0, 0xb5, 0x7f, 0xfe, 0xe6, 0x0f, 0x04, 0xc6, 0x60, 0x1d, 0xe8, 0x00, 0xfe, 0x01, 0x1c, 0x02, 0xfc, + 0x00, 0x3f, 0x85, 0xec, 0x1b, 0xcd, 0xe1, 0xb6, 0xe8, 0xba, 0xfc, 0xb6, 0xb5, 0x62, 0x02, 0x13, 0x30, 0x00, 0x00, 0x0a, 0x04, 0x00, 0x0a, 0x57, 0x02, 0x43, 0x93, 0xe6, 0x29, 0x8b, 0xf8, 0x68, + 0xf2, 0x71, 0x04, 0x7c, 0xf8, 0x65, 0x00, 0x08, 0xf2, 0x7f, 0x7f, 0xf6, 0x0f, 0x05, 0x76, 0x81, 0x2c, 0x80, 0x00, 0xfe, 0x01, 0x1c, 0x02, 0xfc, 0x00, 0x3f, 0x23, 0x00, 0xfa, 0xcd, 0xa1, 0xb2, + 0x58, 0xa2, 0xfa, 0xcf, 0xb5, 0x62, 0x02, 0x13, 0x30, 0x00, 0x00, 0x12, 0x04, 0x00, 0x0a, 0x5f, 0x02, 0x43, 0x93, 0xe6, 0x49, 0x8b, 0x78, 0xed, 0xf3, 0x71, 0x6e, 0x91, 0xd0, 0x65, 0x01, 0xc0, + 0x6f, 0xff, 0x82, 0xfe, 0x0f, 0xee, 0xe0, 0x7f, 0xfc, 0xcf, 0x00, 0xfe, 0x01, 0x1c, 0x02, 0xfc, 0x00, 0x3f, 0x99, 0x0a, 0x00, 0xcd, 0xa1, 0xb4, 0x98, 0xb1, 0x8f, 0x4e, 0xb5, 0x62, 0x02, 0x13, + 0x30, 0x00, 0x00, 0x17, 0x04, 0x00, 0x0a, 0x60, 0x02, 0x43, 0x93, 0xe6, 0x5d, 0x8b, 0x78, 0xe9, 0xb1, 0x71, 0x9a, 0xd4, 0x02, 0x64, 0x01, 0x40, 0x12, 0x00, 0x83, 0xfc, 0x0f, 0xee, 0xef, 0xdf, + 0xfd, 0x07, 0x00, 0xfe, 0x01, 0x1c, 0x02, 0xfc, 0x00, 0x3f, 0x31, 0x0d, 0x00, 0xcd, 0xe1, 0xb5, 0x68, 0xdf, 0xa8, 0x35, 0xb5, 0x62, 0x02, 0x13, 0x30, 0x00, 0x00, 0x01, 0x04, 0x00, 0x0a, 0x61, + 0x02, 0x43, 0x93, 0xe6, 0x05, 0x8b, 0x78, 0xed, 0xdb, 0x71, 0xb0, 0x16, 0x35, 0x64, 0x00, 0x90, 0xde, 0x7f, 0x7e, 0xfa, 0x0f, 0x0a, 0xfa, 0xe0, 0x1e, 0xa4, 0x00, 0xfe, 0x01, 0x1c, 0x02, 0xfc, + 0x00, 0x3f, 0x46, 0x1b, 0x5d, 0xcd, 0x61, 0xb0, 0x28, 0x15, 0x5e, 0xc4, 0xb5, 0x62, 0x02, 0x13, 0x30, 0x00, 0x00, 0x08, 0x04, 0x00, 0x0a, 0x63, 0x02, 0x43, 0x93, 0xe6, 0x21, 0x8b, 0x78, 0xec, + 0x17, 0x72, 0x63, 0x5c, 0xe2, 0x61, 0x00, 0xd8, 0xef, 0xff, 0x7d, 0xeb, 0x0f, 0x0b, 0xc9, 0x60, 0x16, 0x1c, 0x00, 0xfe, 0x01, 0x1c, 0x02, 0xfc, 0x00, 0x3f, 0xd8, 0xa3, 0xee, 0xcd, 0x21, 0xb2, + 0x88, 0x26, 0xc9, 0x59, 0xb5, 0x62, 0x02, 0x15, 0xd0, 0x08, 0xd9, 0xce, 0xf7, 0xd3, 0x58, 0xba, 0x13, 0x41, 0xcd, 0x08, 0x12, 0x46, 0x01, 0x01, 0xf0, 0x75, 0xde, 0x26, 0x6f, 0x09, 0x0d, 0xf3, + 0x7b, 0x41, 0x80, 0x83, 0xfb, 0x04, 0x02, 0x5c, 0xa2, 0x41, 0xc2, 0x12, 0x12, 0x45, 0x02, 0x07, 0x00, 0x00, 0xf4, 0xfb, 0x26, 0x04, 0x02, 0x07, 0x07, 0x00, 0x4a, 0xe5, 0x15, 0x3a, 0x9b, 0xbc, + 0x77, 0x41, 0x4b, 0x97, 0x61, 0x8c, 0x31, 0x2f, 0x9f, 0x41, 0x84, 0xc0, 0x6c, 0xc5, 0x00, 0x10, 0x00, 0x00, 0xf4, 0xfb, 0x29, 0x04, 0x02, 0x07, 0x0f, 0x00, 0x9d, 0x8f, 0x5e, 0x84, 0x52, 0xbc, + 0x7b, 0x41, 0xf8, 0x30, 0x4c, 0xc7, 0x0d, 0x38, 0xa2, 0x41, 0x2a, 0xf0, 0x60, 0xc5, 0x02, 0x15, 0x00, 0x00, 0xf4, 0xfb, 0x26, 0x04, 0x02, 0x07, 0x07, 0x00, 0xa7, 0x4e, 0x91, 0xed, 0xb9, 0xb8, + 0x79, 0x41, 0xdd, 0x32, 0xc8, 0xc1, 0x5e, 0xe5, 0xa0, 0x41, 0xcb, 0xa3, 0x22, 0x45, 0x00, 0x20, 0x00, 0x00, 0xf4, 0xfb, 0x27, 0x05, 0x02, 0x07, 0x07, 0x00, 0x59, 0xb3, 0x78, 0x6b, 0x9a, 0x11, + 0x7a, 0x41, 0xa5, 0xd4, 0x65, 0xb4, 0xc0, 0x1f, 0xa1, 0x41, 0x89, 0x9f, 0x15, 0xc5, 0x02, 0x0d, 0x00, 0x00, 0xf4, 0xfb, 0x2a, 0x04, 0x02, 0x06, 0x07, 0x00, 0xf0, 0x55, 0x81, 0x36, 0x74, 0x42, + 0x78, 0x41, 0xdc, 0x8f, 0x0f, 0xab, 0x0a, 0xdf, 0x9f, 0x41, 0xf0, 0xd3, 0x45, 0xc3, 0x02, 0x1a, 0x00, 0x00, 0xf4, 0xfb, 0x2d, 0x03, 0x01, 0x05, 0x07, 0x00, 0x00, 0xb3, 0x62, 0xe6, 0x30, 0x25, + 0x84, 0x41, 0x7a, 0xaa, 0x50, 0x26, 0xb6, 0x39, 0xaa, 0x41, 0x38, 0x70, 0xba, 0xc4, 0x03, 0x0d, 0x00, 0x00, 0xf4, 0xfb, 0x25, 0x05, 0x03, 0x07, 0x07, 0x00, 0x17, 0xed, 0x9c, 0x69, 0xe1, 0x99, + 0x84, 0x41, 0xf4, 0x93, 0xc6, 0xd2, 0x9e, 0xd1, 0xaa, 0x41, 0xbe, 0x87, 0xcc, 0xc4, 0x03, 0x08, 0x00, 0x00, 0xf4, 0xfb, 0x20, 0x06, 0x06, 0x08, 0x0f, 0x00, 0x2a, 0x81, 0xd2, 0x2c, 0x46, 0x12, + 0x78, 0x41, 0x76, 0x47, 0x56, 0x18, 0x25, 0x56, 0x9f, 0x41, 0x5c, 0x8d, 0xfe, 0x44, 0x03, 0x14, 0x00, 0x00, 0xf4, 0xfb, 0x2d, 0x03, 0x01, 0x06, 0x07, 0x00, 0x6f, 0xba, 0xcb, 0xc3, 0xfb, 0x6d, + 0x79, 0x41, 0xc4, 0x07, 0x26, 0x60, 0x66, 0x8d, 0xa0, 0x41, 0xcd, 0x37, 0x0c, 0x45, 0x03, 0x23, 0x00, 0x00, 0xf4, 0xfb, 0x27, 0x04, 0x02, 0x07, 0x07, 0x00, 0x4d, 0x64, 0x4b, 0xe8, 0x5a, 0x8a, + 0x78, 0x41, 0x5c, 0xba, 0xeb, 0xce, 0x77, 0xf2, 0x9f, 0x41, 0x5c, 0x28, 0x8c, 0xc4, 0x03, 0x20, 0x00, 0x00, 0xf4, 0xfb, 0x2d, 0x03, 0x01, 0x06, 0x0f, 0x00, 0x6d, 0xbc, 0x48, 0xe6, 0x89, 0x2b, + 0x78, 0x41, 0xc6, 0xbb, 0x70, 0xab, 0x08, 0x77, 0x9f, 0x41, 0xfc, 0xc1, 0x1b, 0xc5, 0x03, 0x1e, 0x00, 0x00, 0xf4, 0xfb, 0x2d, 0x03, 0x01, 0x06, 0x07, 0x00, 0xd7, 0x22, 0xa2, 0xb1, 0xeb, 0x84, + 0x78, 0x41, 0x53, 0x30, 0xf9, 0xcb, 0xcc, 0x5d, 0xa0, 0x41, 0xb7, 0x75, 0x95, 0xc5, 0x06, 0x0d, 0x00, 0x05, 0xf4, 0xfb, 0x1c, 0x08, 0x06, 0x08, 0x07, 0x00, 0xef, 0x43, 0x21, 0x05, 0x86, 0x5d, + 0x77, 0x41, 0xb3, 0x43, 0xd4, 0x04, 0xad, 0x39, 0x9f, 0x41, 0x1c, 0x9b, 0x6e, 0x45, 0x06, 0x01, 0x00, 0x08, 0xf4, 0xfb, 0x26, 0x06, 0x03, 0x07, 0x07, 0x00, 0xca, 0x68, 0x8e, 0xb5, 0x70, 0xba, + 0x75, 0x41, 0x10, 0x5e, 0x5b, 0xf0, 0xa8, 0x16, 0x9d, 0x41, 0x44, 0xeb, 0x59, 0x44, 0x06, 0x08, 0x00, 0x0d, 0xf4, 0xfb, 0x2d, 0x05, 0x01, 0x06, 0x07, 0x00, 0xf1, 0x71, 0x8b, 0x44, 0xa0, 0xce, + 0x78, 0x41, 0x6d, 0xd2, 0xfa, 0xfc, 0xee, 0x97, 0xa0, 0x41, 0x78, 0xb5, 0x33, 0x45, 0x06, 0x11, 0x00, 0x0b, 0x08, 0x9d, 0x24, 0x06, 0x03, 0x08, 0x07, 0x00, 0xd6, 0x24, 0xe5, 0x9a, 0x02, 0x55, + 0x77, 0x41, 0x90, 0xae, 0x11, 0xce, 0x7d, 0x2b, 0x9f, 0x41, 0x24, 0xe5, 0xb2, 0x44, 0x06, 0x0f, 0x00, 0x07, 0xf4, 0xfb, 0x2a, 0x05, 0x02, 0x07, 0x0f, 0x00, 0xab, 0x8e, 0xc3, 0x9a, 0x9f, 0xe8, + 0x78, 0x41, 0x91, 0x54, 0x5d, 0xe5, 0xda, 0x9e, 0xa0, 0x41, 0x0d, 0xdf, 0x66, 0xc5, 0x06, 0x16, 0x00, 0x04, 0xf4, 0xfb, 0x27, 0x06, 0x02, 0x07, 0x07, 0x00, 0x35, 0x98, 0xbb, 0x15, 0x9a, 0x2e, + 0x83, 0x41, 0x82, 0x14, 0xcb, 0xd3, 0x58, 0x33, 0xa9, 0x41, 0x78, 0xe2, 0xd3, 0xc3, 0x01, 0x88, 0x00, 0x00, 0xf4, 0xfb, 0x29, 0x04, 0x02, 0x07, 0x0f, 0x00, 0x7a, 0x99, 0x39, 0x06, 0x80, 0xef, + 0x75, 0x41, 0x74, 0xa3, 0x81, 0xc3, 0x6b, 0xd1, 0x9c, 0x41, 0x3c, 0x3b, 0x17, 0xc4, 0x00, 0x0a, 0x00, 0x00, 0xf4, 0xfb, 0x31, 0x03, 0x01, 0x05, 0x0f, 0x00, 0xe9, 0xb9, 0x44, 0x1e, 0x05, 0xe4, + 0x83, 0x41, 0xc6, 0x4a, 0x46, 0xb6, 0xaf, 0x21, 0xaa, 0x41, 0xe8, 0x7c, 0xcf, 0xc3, 0x01, 0x7f, 0x00, 0x00, 0x50, 0xdc, 0x1f, 0x06, 0x05, 0x08, 0x0f, 0x00, 0x72, 0xd9, 0xbb, 0xf9, 0xad, 0x5c, + 0x83, 0x41, 0x00, 0x2d, 0xee, 0xc6, 0xe1, 0x6f, 0xa9, 0x41, 0x10, 0xd9, 0xd4, 0xc3, 0x01, 0x7b, 0x00, 0x00, 0xf4, 0xfb, 0x27, 0x04, 0x02, 0x07, 0x0f, 0x00, 0x7a, 0xd2, 0x24, 0xc9, 0xfe, 0x3a, + 0x77, 0x41, 0x77, 0x3d, 0x2d, 0x9d, 0xeb, 0x84, 0x9e, 0x41, 0x7b, 0x39, 0x31, 0xc5, 0x00, 0x17, 0x00, 0x00, 0xf4, 0xfb, 0x2c, 0x03, 0x01, 0x06, 0x07, 0x00, 0xcc, 0x1f, 0x95, 0x0c, 0xd2, 0xa6, + 0x76, 0x41, 0x50, 0x45, 0x5c, 0xa2, 0xff, 0x7c, 0x9d, 0x41, 0xf1, 0x18, 0x59, 0x43, 0x03, 0x1d, 0x00, 0x00, 0xf4, 0xfb, 0x2f, 0x03, 0x01, 0x05, 0x07, 0x00, 0x09, 0x8f, 0xf1, 0xe4, 0xb0, 0x04, + 0x7a, 0x41, 0xee, 0x99, 0x1c, 0xa6, 0x7e, 0xef, 0xa0, 0x41, 0x76, 0xb6, 0x39, 0xc5, 0x03, 0x2d, 0x00, 0x00, 0xf4, 0xfb, 0x28, 0x04, 0x02, 0x07, 0x07, 0x00, 0x27, 0x7e, 0xe9, 0x03, 0x6a, 0x15, + 0x77, 0x41, 0x4d, 0x3a, 0x89, 0xf3, 0x64, 0xe4, 0x9e, 0x41, 0xcf, 0xd2, 0x2b, 0xc5, 0x06, 0x07, 0x00, 0x0c, 0xf4, 0xfb, 0x2b, 0x05, 0x01, 0x06, 0x0f, 0x00, 0xe0, 0x1d, 0xa4, 0x15, 0xb7, 0x16, + 0x75, 0x41, 0x24, 0x4b, 0x28, 0x2c, 0xde, 0x33, 0x9c, 0x41, 0x83, 0xa2, 0xdc, 0xc4, 0x06, 0x17, 0x00, 0x0a, 0xf4, 0xfb, 0x2b, 0x05, 0x01, 0x06, 0x07, 0x00, 0x96, 0xb8, 0x46, 0xfd, 0xd0, 0x4c, + 0x76, 0x41, 0x14, 0x0c, 0xb3, 0xab, 0xce, 0xb7, 0x9d, 0x41, 0xc1, 0xfa, 0x10, 0xc5, 0x06, 0x0e, 0x00, 0x00, 0xf4, 0xfb, 0x2a, 0x05, 0x01, 0x06, 0x0f, 0x00, 0xcd, 0x5d, 0xd7, 0xd5, 0xa3, 0x37, + 0x75, 0x41, 0xc6, 0xc6, 0x3f, 0xe1, 0x5c, 0x5d, 0x9c, 0x41, 0x92, 0x12, 0xa3, 0x44, 0x06, 0x18, 0x00, 0x09, 0xf4, 0xfb, 0x2e, 0x05, 0x01, 0x06, 0x07, 0x00, 0xf4, 0xd2, 0x9b, 0xd9, 0x47, 0xc7, + 0x7a, 0x41, 0x34, 0x4d, 0x20, 0xc6, 0x19, 0x97, 0xa1, 0x41, 0xd8, 0xd2, 0xce, 0x44, 0x02, 0x21, 0x00, 0x00, 0xf4, 0xfb, 0x28, 0x04, 0x02, 0x07, 0x07, 0x00, 0x1b, 0xa7, 0x9f, 0xc5, 0xdb, 0x5e, + 0x7a, 0x41, 0xa6, 0x2c, 0xa8, 0xf8, 0x7f, 0x52, 0xa1, 0x41, 0x7f, 0x01, 0x71, 0xc4, 0x00, 0x1e, 0x00, 0x00, 0xf4, 0xfb, 0x26, 0x05, 0x02, 0x07, 0x0f, 0x00, 0xa5, 0x3b, 0x59, 0x8c, 0xad, 0x52, + 0x77, 0x41, 0xca, 0xbb, 0xae, 0x1c, 0x0a, 0xa4, 0x9e, 0x41, 0xb8, 0x8d, 0xdc, 0x44, 0x00, 0x15, 0x00, 0x00, 0xf4, 0xfb, 0x2b, 0x04, 0x02, 0x06, 0x0f, 0x00, 0xcf, 0x1e, 0x77, 0x4f, 0xdf, 0x03, + 0x7d, 0x41, 0xf3, 0xc0, 0x3d, 0xdd, 0x37, 0x0f, 0xa3, 0x41, 0xd4, 0xe7, 0xd6, 0xc4, 0x02, 0x03, 0x00, 0x00, 0xf4, 0xfb, 0x25, 0x04, 0x02, 0x07, 0x07, 0x00, 0x43, 0xeb, 0xfe, 0xec, 0x08, 0x7c, + 0x79, 0x41, 0xfc, 0x61, 0xaf, 0x2a, 0x81, 0xbd, 0xa0, 0x41, 0x29, 0xbc, 0x01, 0xc5, 0x02, 0x01, 0x00, 0x00, 0xf4, 0xfb, 0x2c, 0x04, 0x01, 0x06, 0x07, 0x00, 0x59, 0x73, 0xb7, 0x5d, 0x17, 0xc9, + 0x75, 0x41, 0xc6, 0x75, 0xe1, 0x8d, 0xf5, 0x9e, 0x9c, 0x41, 0x40, 0x20, 0x7e, 0x44, 0x00, 0x08, 0x00, 0x00, 0xf4, 0xfb, 0x2e, 0x03, 0x01, 0x05, 0x07, 0x00, 0xf4, 0x9c, 0xfc, 0xcb, 0x7b, 0x9d, + 0x79, 0x41, 0xd3, 0xb3, 0x6c, 0xb1, 0x79, 0xd3, 0xa0, 0x41, 0x39, 0x9c, 0x63, 0xc5, 0x00, 0x12, 0x00, 0x00, 0xf4, 0xfb, 0x29, 0x04, 0x02, 0x07, 0x0f, 0x00, 0xb5, 0x6e, 0x7b, 0x6b, 0x6f, 0x46, + 0x75, 0x41, 0x7d, 0xa1, 0xc4, 0xe7, 0x4d, 0xf3, 0x9b, 0x41, 0xae, 0xc0, 0xa0, 0xc4, 0x00, 0x1b, 0x00, 0x00, 0xf4, 0xfb, 0x2f, 0x03, 0x01, 0x05, 0x0f, 0x00, 0x46, 0xef, 0x15, 0xd0, 0x09, 0x89, + 0x79, 0x41, 0xa7, 0x2b, 0xc7, 0x0d, 0x0c, 0xc6, 0xa0, 0x41, 0x70, 0xec, 0x3d, 0x45, 0x00, 0x01, 0x00, 0x00, 0xf4, 0xfb, 0x27, 0x05, 0x02, 0x07, 0x0f, 0x00, 0x83, 0x06, 0x3b, 0xe3, 0xd9, 0x0f, + 0x7a, 0x41, 0x36, 0x6e, 0x47, 0x03, 0x9a, 0x1e, 0xa1, 0x41, 0x02, 0x93, 0x08, 0xc5, 0x00, 0x07, 0x00, 0x00, 0xf4, 0xfb, 0x1a, 0x06, 0x07, 0x08, 0x07, 0x00, 0x52, 0xda, 0x74, 0xb9, 0x41, 0xd2, + 0x7a, 0x41, 0x0c, 0x02, 0x6d, 0xea, 0x4d, 0x9e, 0xa1, 0x41, 0x80, 0x4b, 0x63, 0x44, 0x02, 0x1f, 0x00, 0x00, 0xf4, 0xfb, 0x2a, 0x04, 0x01, 0x06, 0x07, 0x00, 0x74, 0x88, 0x81, 0x91, 0xfe, 0x4d, + 0x7b, 0x41, 0x7f, 0x89, 0x52, 0x79, 0x95, 0xef, 0xa1, 0x41, 0x74, 0x9f, 0x0b, 0x44, 0x02, 0x08, 0x00, 0x00, 0xf4, 0xfb, 0x29, 0x04, 0x02, 0x06, 0x07, 0x00, 0x1f, 0xda, 0xb6, 0x4d, 0x74, 0x42, + 0x78, 0x41, 0xa8, 0x84, 0x0d, 0x3f, 0xbc, 0x6b, 0x98, 0x41, 0x80, 0x90, 0x17, 0xc3, 0x02, 0x1a, 0x06, 0x00, 0xf4, 0xfb, 0x31, 0x03, 0x01, 0x04, 0x07, 0x00, 0xaf, 0x44, 0xd3, 0xb2, 0x9a, 0x11, + 0x7a, 0x41, 0xda, 0x48, 0xef, 0x97, 0xf5, 0x3d, 0x9a, 0x41, 0x96, 0x4b, 0xe5, 0xc4, 0x02, 0x0d, 0x06, 0x00, 0xf4, 0xfb, 0x30, 0x03, 0x01, 0x04, 0x07, 0x00, 0x47, 0x19, 0x48, 0xec, 0x52, 0xbc, + 0x7b, 0x41, 0x6a, 0x5f, 0xc5, 0xac, 0x82, 0xeb, 0x9b, 0x41, 0x30, 0x58, 0x2c, 0xc5, 0x02, 0x15, 0x06, 0x00, 0xf4, 0xfb, 0x29, 0x03, 0x02, 0x06, 0x07, 0x00, 0x3b, 0xa1, 0xe2, 0x21, 0x09, 0x7c, + 0x79, 0x41, 0xf3, 0x2f, 0xce, 0xbf, 0x65, 0xa7, 0x99, 0x41, 0x72, 0xc8, 0xc6, 0xc4, 0x02, 0x01, 0x06, 0x00, 0xf4, 0xfb, 0x2f, 0x03, 0x01, 0x05, 0x07, 0x00, 0x17, 0xbc, 0xab, 0x35, 0xe1, 0x99, + 0x84, 0x41, 0xf2, 0x60, 0x0c, 0x8b, 0xee, 0xbc, 0xa4, 0x41, 0xc8, 0x1e, 0x9e, 0xc4, 0x03, 0x08, 0x02, 0x00, 0xf4, 0xfb, 0x24, 0x04, 0x03, 0x07, 0x07, 0x00, 0xf6, 0x74, 0xa8, 0x71, 0x0d, 0xf3, + 0x7b, 0x41, 0x44, 0x2f, 0xc1, 0x72, 0x9c, 0x22, 0x9c, 0x41, 0xc8, 0xd3, 0xdf, 0x44, 0x02, 0x07, 0x06, 0x00, 0xf4, 0xfb, 0x2a, 0x03, 0x02, 0x06, 0x07, 0x00, 0xd0, 0x5d, 0x47, 0xf7, 0x30, 0x25, + 0x84, 0x41, 0xc9, 0xac, 0x40, 0xb2, 0x77, 0x47, 0xa4, 0x41, 0xb2, 0x27, 0x90, 0xc4, 0x03, 0x0d, 0x02, 0x00, 0xf4, 0xfb, 0x28, 0x04, 0x02, 0x07, 0x07, 0x00, 0x40, 0xaf, 0xd5, 0x9b, 0xdf, 0x03, + 0x7d, 0x41, 0x73, 0x4f, 0x2e, 0x9b, 0x3e, 0x35, 0x9d, 0x41, 0x9f, 0xb4, 0xa4, 0xc4, 0x02, 0x03, 0x06, 0x00, 0xf4, 0xfb, 0x27, 0x03, 0x02, 0x07, 0x07, 0x00, 0x1a, 0x97, 0x37, 0x17, 0x48, 0xc7, + 0x7a, 0x41, 0x30, 0xdb, 0x48, 0xc8, 0xdb, 0xf4, 0x9a, 0x41, 0x12, 0x7a, 0x9e, 0x44, 0x02, 0x21, 0x06, 0x00, 0xf4, 0xfb, 0x2f, 0x03, 0x01, 0x05, 0x07, 0x00, 0xa4, 0xfd, 0xb6, 0x0b, 0x42, 0xd2, + 0x7a, 0x41, 0x2e, 0xdd, 0xe9, 0x8e, 0xe5, 0xff, 0x9a, 0x41, 0x64, 0x33, 0x2e, 0x44, 0x02, 0x1f, 0x06, 0x00, 0xf4, 0xfb, 0x2e, 0x03, 0x01, 0x05, 0x07, 0x00, 0xca, 0x06, 0x7e, 0xb3, 0xfe, 0x4d, + 0x7b, 0x41, 0x9e, 0xbe, 0x0f, 0x6c, 0x75, 0x7c, 0x9b, 0x41, 0x78, 0x01, 0xd6, 0x43, 0x02, 0x08, 0x06, 0x00, 0xf4, 0xfb, 0x2a, 0x03, 0x02, 0x06, 0x07, 0x00, 0x23, 0x73, 0xeb, 0x5e, 0x6f, 0x46, + 0x75, 0x41, 0x5f, 0xc8, 0x2f, 0x21, 0x90, 0xc7, 0x95, 0x41, 0x11, 0x83, 0x7a, 0xc4, 0x00, 0x1b, 0x03, 0x00, 0xf4, 0xfb, 0x2b, 0x04, 0x01, 0x06, 0x07, 0x00, 0x42, 0x05, 0xea, 0x24, 0x33, 0x3f, + 0x7a, 0x41, 0xd1, 0xc6, 0x57, 0xfb, 0x7f, 0xde, 0x9a, 0x41, 0x9f, 0x7f, 0x46, 0xc5, 0x00, 0x1a, 0x03, 0x00, 0x00, 0x00, 0x0f, 0x09, 0x0f, 0x0c, 0x01, 0x00, 0xe0, 0x2f, 0xe6, 0x2a, 0xba, 0xb8, + 0x79, 0x41, 0x85, 0xd0, 0x08, 0x34, 0xdb, 0x54, 0x9a, 0x41, 0x21, 0x7e, 0xfd, 0x44, 0x00, 0x20, 0x03, 0x00, 0xf4, 0xfb, 0x24, 0x05, 0x03, 0x08, 0x07, 0x00, 0x01, 0xb5, 0xac, 0xf7, 0x7f, 0xef, + 0x75, 0x41, 0x02, 0x5c, 0xbe, 0xb5, 0xa4, 0x74, 0x96, 0x41, 0xb8, 0x97, 0xeb, 0xc3, 0x00, 0x0a, 0x03, 0x00, 0xf4, 0xfb, 0x2b, 0x04, 0x01, 0x06, 0x07, 0x00, 0x4c, 0xd8, 0x34, 0xe1, 0x9f, 0xe8, + 0x78, 0x41, 0x66, 0xa1, 0xa6, 0xf8, 0xa8, 0xda, 0x99, 0x41, 0x7e, 0x8c, 0x33, 0xc5, 0x06, 0x16, 0x02, 0x04, 0xf4, 0xfb, 0x27, 0x06, 0x02, 0x07, 0x07, 0x00, 0x25, 0xf5, 0xcf, 0x47, 0xd1, 0x4c, + 0x76, 0x41, 0x22, 0xc4, 0x12, 0xd0, 0x2d, 0x1d, 0x97, 0x41, 0x6a, 0x81, 0xe1, 0xc4, 0x06, 0x0e, 0x02, 0x00, 0xf4, 0xfb, 0x2a, 0x05, 0x01, 0x06, 0x0f, 0x00, 0x9d, 0x7e, 0xc9, 0x85, 0x86, 0x5d, + 0x77, 0x41, 0x64, 0x0f, 0x99, 0x84, 0x4f, 0x49, 0x98, 0x41, 0xee, 0x8e, 0x39, 0x45, 0x06, 0x01, 0x02, 0x08, 0xf4, 0xfb, 0x22, 0x06, 0x04, 0x08, 0x07, 0x00, 0x75, 0x62, 0xb4, 0xdd, 0x02, 0x55, + 0x77, 0x41, 0x3b, 0xc0, 0x85, 0xbb, 0x45, 0x3e, 0x98, 0x41, 0x3e, 0x28, 0x8b, 0x44, 0x06, 0x0f, 0x02, 0x07, 0xf4, 0xfb, 0x29, 0x05, 0x02, 0x07, 0x07, 0x00, 0x7d, 0x7a, 0x3e, 0xfa, 0xdb, 0x5e, + 0x7a, 0x41, 0x64, 0x49, 0x93, 0x4d, 0xe9, 0xfe, 0x9a, 0x41, 0xf0, 0x04, 0x3c, 0xc4, 0x00, 0x1e, 0x03, 0x00, 0xf4, 0xfb, 0x20, 0x06, 0x05, 0x08, 0x0f, 0x00, 0x23, 0x8e, 0x44, 0xb8, 0x7b, 0x9d, + 0x79, 0x41, 0xfe, 0xc4, 0xed, 0x80, 0xf2, 0x38, 0x9a, 0x41, 0x5c, 0x58, 0x31, 0xc5, 0x00, 0x12, 0x03, 0x00, 0xf4, 0xfb, 0x24, 0x05, 0x03, 0x08, 0x0f, 0x00, 0xf2, 0xd8, 0x32, 0xaf, 0xfe, 0x3a, + 0x77, 0x41, 0x85, 0x0a, 0xa8, 0x63, 0xfd, 0xc7, 0x97, 0x41, 0x3f, 0x18, 0x0a, 0xc5, 0x00, 0x17, 0x03, 0x00, 0xf4, 0xfb, 0x2a, 0x04, 0x01, 0x06, 0x07, 0x00, 0x31, 0xa1, 0xe3, 0x42, 0x0a, 0x89, + 0x79, 0x41, 0xb4, 0x05, 0x14, 0xf4, 0x05, 0x24, 0x9a, 0x41, 0x66, 0x09, 0x14, 0x45, 0x00, 0x01, 0x03, 0x00, 0xf4, 0xfb, 0x24, 0x05, 0x04, 0x08, 0x07, 0x00, 0xdc, 0x4b, 0xf4, 0x75, 0xd9, 0x0f, + 0x7a, 0x41, 0x50, 0x59, 0x53, 0xec, 0x06, 0xae, 0x9a, 0x41, 0x2c, 0x6b, 0xd4, 0xc4, 0x00, 0x07, 0x03, 0x00, 0x00, 0x00, 0x16, 0x09, 0x0f, 0x0c, 0x01, 0x00, 0xcb, 0xa6, 0x17, 0x6d, 0x17, 0xc9, + 0x75, 0x41, 0xd7, 0x2c, 0x19, 0xd3, 0x50, 0x4d, 0x96, 0x41, 0xd4, 0x0a, 0x46, 0x44, 0x00, 0x08, 0x03, 0x00, 0xf4, 0xfb, 0x2c, 0x04, 0x01, 0x06, 0x07, 0x00, 0x89, 0x46, 0xe8, 0x41, 0xec, 0x84, + 0x78, 0x41, 0xb7, 0x12, 0xf9, 0xca, 0x76, 0x75, 0x99, 0x41, 0x0e, 0x77, 0x68, 0xc5, 0x06, 0x0d, 0x02, 0x05, 0xf4, 0xfb, 0x20, 0x07, 0x05, 0x08, 0x0f, 0x00, 0x73, 0x17, 0xf9, 0xba, 0x70, 0xba, + 0x75, 0x41, 0x5d, 0xbb, 0x16, 0xe9, 0xda, 0x9f, 0x96, 0x41, 0xb9, 0x88, 0x29, 0x44, 0x06, 0x08, 0x02, 0x0d, 0xf4, 0xfb, 0x2a, 0x05, 0x02, 0x06, 0x07, 0x00, 0x74, 0xce, 0xda, 0xef, 0xa3, 0x37, + 0x75, 0x41, 0x37, 0xbf, 0xfc, 0xb2, 0xbe, 0x0f, 0x96, 0x41, 0x2f, 0xb3, 0x7d, 0x44, 0x06, 0x18, 0x02, 0x09, 0xf4, 0xfb, 0x2c, 0x05, 0x01, 0x06, 0x07, 0x00, 0xc1, 0x45, 0x47, 0x27, 0x6a, 0x15, + 0x77, 0x41, 0x47, 0xdb, 0xa1, 0x7a, 0xf7, 0x06, 0x98, 0x41, 0xf1, 0xa9, 0x05, 0xc5, 0x06, 0x07, 0x02, 0x0c, 0xf4, 0xfb, 0x27, 0x06, 0x02, 0x07, 0x07, 0x00, 0xa4, 0x8a, 0xb5, 0x62, 0x0a, 0x06, + 0x78, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x32, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0xa4, 0x9f, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x2e, 0x47, 0x06, 0x00, 0x00, 0x00, 0x00, 0x00, 0x78, 0xca, 0xb5, 0x62, 0x0a, 0x36, + 0x80, 0x00, 0x00, 0x03, 0x00, 0x00, 0x00, 0x01, 0x05, 0x06, 0x00, 0x02, 0x00, 0x00, 0x32, 0x83, 0x0b, 0x05, 0x05, 0x0b, 0x00, 0x00, 0x19, 0x1c, 0xf2, 0x14, 0x06, 0x15, 0x00, 0x00, 0x24, 0xc0, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x85, 0x00, 0x00, 0x00, 0x00, 0x04, 0x18, 0x00, 0x07, 0x2b, 0x96, 0x0e, 0x0b, 0x37, 0x00, 0x00, 0x02, 0xc3, + 0x67, 0x00, 0x06, 0x10, 0x00, 0x00, 0x32, 0x00, 0x00, 0x00, 0xa4, 0x9f, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x2e, 0x47, 0x06, 0x00, 0x01, 0x01, 0x00, 0x00, 0x1c, 0xed, + 0xf1, 0x14, 0x08, 0x0a, 0x00, 0x00, 0x16, 0x3d, 0x02, 0x05, 0x06, 0x12, 0x00, 0x00, 0x69, 0x4f, 0x00, 0x00, 0xa4, 0x9f, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x5a, 0xcf, 0xb5, 0x62, 0x0a, 0x37, 0xe2, 0x00, 0x00, 0x22, 0x01, 0x30, 0x30, 0x31, 0x39, 0x30, 0x30, 0x30, 0x30, 0x00, 0x00, 0x03, 0x0e, 0x5a, 0x0e, 0x5a, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x41, 0x08, 0x3e, 0x00, 0x00, 0x01, 0x64, 0x08, 0x06, 0x00, 0x00, 0x02, 0x44, 0x08, 0x07, 0x00, 0x00, 0x03, 0x64, 0x08, 0x09, 0x00, 0x00, 0x04, 0x44, 0x08, 0x08, 0x00, 0x00, 0x05, + 0x40, 0x08, 0x10, 0x00, 0x00, 0x06, 0x21, 0x09, 0xff, 0x00, 0x00, 0x07, 0x41, 0x09, 0x12, 0x00, 0x00, 0x08, 0x41, 0x09, 0x13, 0x00, 0x00, 0x09, 0x60, 0x09, 0x14, 0x00, 0x00, 0x0a, 0x60, 0x08, + 0x15, 0x00, 0x00, 0x0b, 0x40, 0x09, 0x0e, 0x00, 0x00, 0x0c, 0x40, 0x09, 0x0a, 0x00, 0x00, 0x0d, 0x60, 0x09, 0x0b, 0x00, 0x00, 0x0e, 0x60, 0x09, 0x0f, 0x00, 0x00, 0x0f, 0x51, 0x08, 0x44, 0x00, + 0x00, 0x10, 0x44, 0x08, 0x16, 0x00, 0x01, 0x00, 0x21, 0x09, 0xff, 0x00, 0x01, 0x01, 0x60, 0x09, 0x00, 0x00, 0x01, 0x02, 0x60, 0x08, 0x01, 0x00, 0x01, 0x03, 0x21, 0x09, 0xff, 0x00, 0x01, 0x04, + 0x51, 0x08, 0x46, 0x00, 0x01, 0x05, 0x21, 0x09, 0xff, 0x00, 0x01, 0x06, 0x21, 0x09, 0xff, 0x00, 0x01, 0x07, 0x41, 0x09, 0x12, 0x00, 0x01, 0x08, 0x61, 0x09, 0x13, 0x00, 0x01, 0x09, 0x60, 0x09, + 0x14, 0x00, 0x01, 0x0a, 0x60, 0x08, 0x15, 0x00, 0x01, 0x0b, 0x21, 0x09, 0xff, 0x00, 0x01, 0x0c, 0x21, 0x09, 0xff, 0x00, 0x01, 0x0d, 0x21, 0x09, 0xff, 0x00, 0x01, 0x0e, 0x61, 0x09, 0x34, 0x00, + 0x01, 0x0f, 0xe1, 0x09, 0x36, 0x00, 0x01, 0x10, 0x51, 0x08, 0x35, 0x00, 0x51, 0x82, 0xb5, 0x62, 0x0a, 0x38, 0x34, 0x00, 0x00, 0x02, 0x00, 0x00, 0x00, 0x00, 0x02, 0x01, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x4f, 0x00, 0x0d, 0x1a, 0x2a, 0x0d, 0x9f, 0x07, 0x92, 0x00, 0x00, 0x00, 0x01, 0x00, 0x02, 0x01, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x33, 0x00, 0x0d, 0x1a, + 0x23, 0x0f, 0x9f, 0x06, 0x9c, 0x00, 0x00, 0x00, 0x31, 0x79, 0xb5, 0x62, 0x0a, 0x31, 0x24, 0x02, 0x00, 0x02, 0x00, 0x00, 0x48, 0x45, 0x43, 0x45, 0x47, 0x45, 0x45, 0x45, 0x47, 0x44, 0x48, 0x46, + 0x48, 0x48, 0x47, 0x49, 0x48, 0x49, 0x49, 0x4a, 0x4c, 0x4d, 0x4d, 0x50, 0x4f, 0x4f, 0x50, 0x4f, 0x54, 0x53, 0x58, 0x66, 0xa7, 0x6c, 0x66, 0x57, 0x55, 0x58, 0x57, 0x5a, 0x53, 0x58, 0x58, 0x57, + 0x57, 0x55, 0x5a, 0x5c, 0x5c, 0x63, 0x61, 0x64, 0x64, 0x63, 0x66, 0x69, 0x69, 0x66, 0x68, 0x6c, 0x6d, 0x6c, 0x6d, 0x6f, 0x77, 0x7a, 0x78, 0x78, 0x77, 0x79, 0x79, 0x7c, 0x7e, 0x7e, 0x7f, 0x80, + 0x82, 0x82, 0x85, 0x88, 0x88, 0x8a, 0x89, 0x88, 0x86, 0x86, 0x87, 0x85, 0x86, 0x85, 0x93, 0x87, 0x86, 0x84, 0x85, 0x86, 0x9c, 0x86, 0x87, 0x85, 0x85, 0x84, 0x82, 0x83, 0x83, 0x84, 0x84, 0x84, + 0x85, 0x8c, 0x90, 0x8d, 0x8d, 0x8c, 0x88, 0x87, 0x88, 0x89, 0x89, 0x8a, 0x8a, 0x92, 0x8c, 0x8d, 0x91, 0x90, 0x91, 0x98, 0x94, 0x92, 0x91, 0x92, 0x92, 0xb4, 0x95, 0x90, 0x8e, 0x8e, 0x8f, 0x8d, + 0x8f, 0x8d, 0x8e, 0x8b, 0x8d, 0x88, 0x89, 0x88, 0x86, 0x86, 0x84, 0x85, 0x85, 0x81, 0x81, 0x83, 0x82, 0x84, 0x84, 0x87, 0xb4, 0x8b, 0x85, 0x84, 0x85, 0x84, 0x85, 0x85, 0x86, 0x88, 0x8a, 0x87, + 0x86, 0x86, 0x86, 0x86, 0x88, 0x87, 0x83, 0x83, 0x82, 0x81, 0x7f, 0x7f, 0x7d, 0x7c, 0x7b, 0x78, 0x76, 0x75, 0x7b, 0x71, 0x71, 0x6c, 0x6a, 0x69, 0x66, 0x64, 0x63, 0x61, 0x62, 0x60, 0x60, 0x5e, + 0x5d, 0x5d, 0x5a, 0x5a, 0x59, 0x59, 0x67, 0x57, 0x55, 0x54, 0x55, 0x54, 0x54, 0x53, 0x51, 0x4f, 0x57, 0x51, 0x5b, 0x4e, 0x54, 0x4e, 0x4b, 0x4b, 0x4a, 0x4c, 0x4a, 0x4b, 0x53, 0x4c, 0x49, 0x48, + 0x48, 0x47, 0x48, 0x47, 0x46, 0x46, 0x45, 0x47, 0x46, 0x45, 0x44, 0x45, 0x44, 0x4d, 0x45, 0x46, 0x45, 0x45, 0x46, 0x46, 0x00, 0x20, 0xa1, 0x07, 0x20, 0xa1, 0x07, 0x00, 0x82, 0xb3, 0x61, 0x5e, + 0x39, 0x00, 0x00, 0x00, 0x47, 0x48, 0x46, 0x48, 0x47, 0x46, 0x48, 0x48, 0x49, 0x48, 0x48, 0x49, 0x4a, 0x4a, 0x4a, 0x4d, 0x4b, 0x4c, 0x4b, 0x4c, 0x52, 0x4e, 0x4c, 0x4e, 0x50, 0x50, 0x4f, 0x53, + 0x58, 0x57, 0x58, 0x54, 0x57, 0x5a, 0x59, 0x59, 0x5a, 0x5d, 0x5c, 0x5e, 0x60, 0x63, 0x63, 0x62, 0x63, 0x64, 0x65, 0x69, 0x68, 0x69, 0x6b, 0x6d, 0x6f, 0x72, 0x73, 0x76, 0x76, 0x79, 0x7c, 0x96, + 0x7e, 0x7e, 0x80, 0x82, 0x84, 0x85, 0x85, 0x88, 0x89, 0x88, 0x89, 0x8c, 0x8a, 0x8a, 0x8a, 0x8a, 0x8b, 0x8b, 0x8e, 0xb1, 0x8d, 0x8d, 0x8c, 0x8c, 0x8c, 0x8a, 0x8c, 0x8e, 0x8c, 0x8b, 0x8d, 0x8e, + 0x8e, 0x8d, 0x8c, 0x8f, 0x8e, 0x8d, 0x8b, 0x8b, 0x8c, 0x8c, 0x8b, 0x8c, 0x8c, 0x8b, 0x8d, 0x8d, 0x8b, 0x89, 0x89, 0x91, 0x8b, 0x8c, 0x8d, 0x8e, 0x8d, 0x8e, 0x8e, 0x8d, 0x8e, 0x8e, 0x8e, 0x8f, + 0x90, 0x91, 0x94, 0xa4, 0x93, 0x92, 0x91, 0x8d, 0x8e, 0x8f, 0x91, 0x8e, 0x8d, 0x8d, 0x8d, 0x8c, 0x8c, 0x8d, 0x8c, 0x8c, 0x8a, 0x8b, 0x8a, 0x89, 0x89, 0x8b, 0x89, 0x88, 0x89, 0x89, 0x88, 0x89, + 0x89, 0x89, 0xa3, 0x89, 0x89, 0x8a, 0x89, 0x89, 0x89, 0x89, 0x88, 0x89, 0x8b, 0x8b, 0x8a, 0x8a, 0x8b, 0x8c, 0x8b, 0x8e, 0x8b, 0x8a, 0x8c, 0x90, 0x8b, 0x8a, 0x89, 0x8a, 0x89, 0x88, 0x88, 0x86, + 0x85, 0x85, 0x83, 0x81, 0x7e, 0x7d, 0x7b, 0x7a, 0x76, 0x75, 0x73, 0x70, 0x6f, 0x6e, 0x6a, 0x6a, 0x68, 0x68, 0x65, 0x63, 0x62, 0x5f, 0x5e, 0x5d, 0x5b, 0x59, 0x59, 0x59, 0x56, 0x55, 0x56, 0x53, + 0x53, 0x50, 0x51, 0x50, 0x50, 0x51, 0x56, 0x4e, 0x4c, 0x4c, 0x4d, 0x4b, 0x4a, 0x4a, 0x4a, 0x4a, 0x4a, 0x49, 0x4a, 0x68, 0x4a, 0x48, 0x48, 0x4a, 0x48, 0x48, 0x47, 0x48, 0x47, 0x47, 0x46, 0x46, + 0x46, 0x47, 0x47, 0x47, 0x00, 0x20, 0xa1, 0x07, 0x20, 0xa1, 0x07, 0x00, 0x6a, 0xda, 0xf4, 0x48, 0x39, 0x00, 0x00, 0x00, 0xe6, 0x81, 0xb5, 0x62, 0x02, 0x13, 0x30, 0x00, 0x03, 0x1d, 0x00, 0x00, + 0x0a, 0x18, 0x02, 0x00, 0xe4, 0x34, 0x90, 0x38, 0xf6, 0xe3, 0x08, 0x3a, 0xf6, 0x65, 0x4e, 0x24, 0x1e, 0x80, 0x28, 0x17, 0xc9, 0xfd, 0x77, 0x03, 0x4d, 0x00, 0x6a, 0x26, 0x49, 0xa2, 0x9f, 0x05, + 0x78, 0xef, 0x44, 0x0f, 0x0b, 0x41, 0xf9, 0x02, 0xe2, 0x2c, 0xd9, 0x3c, 0xfe, 0x19, 0xb5, 0x62, 0x02, 0x13, 0x30, 0x00, 0x03, 0x14, 0x00, 0x00, 0x0a, 0x08, 0x02, 0x00, 0xe4, 0x34, 0x90, 0x38, + 0xf6, 0xe3, 0x08, 0x3a, 0xfa, 0x3b, 0x4f, 0x24, 0x44, 0x00, 0x0e, 0x02, 0x89, 0xfd, 0xb7, 0x02, 0xdb, 0xff, 0xd1, 0x2f, 0x8a, 0x9b, 0x81, 0x36, 0x31, 0x80, 0x11, 0x1a, 0xac, 0x0c, 0xe7, 0x3f, + 0x44, 0xe4, 0x07, 0x05, 0x4a, 0x83, 0xb5, 0x62, 0x02, 0x13, 0x30, 0x00, 0x03, 0x1e, 0x00, 0x00, 0x0a, 0x0b, 0x02, 0x00, 0xe4, 0x34, 0x90, 0x38, 0xf6, 0xe3, 0x08, 0x3a, 0xf5, 0x64, 0x4e, 0x24, + 0xb3, 0x7f, 0x4c, 0x14, 0x99, 0xfd, 0x47, 0x3e, 0x99, 0x00, 0x94, 0x27, 0x73, 0xce, 0xbf, 0x0d, 0x74, 0x97, 0x45, 0x0f, 0x7b, 0x90, 0x70, 0x3b, 0x1f, 0xde, 0xa3, 0x19, 0x1f, 0x0d, 0xb5, 0x62, + 0x02, 0x13, 0x30, 0x00, 0x03, 0x20, 0x00, 0x00, 0x0a, 0x0a, 0x02, 0x00, 0xe4, 0x34, 0x90, 0x38, 0xf6, 0xe3, 0x08, 0x3a, 0xf1, 0x20, 0x4f, 0x24, 0x1e, 0x80, 0x58, 0x2e, 0xa9, 0xfd, 0x9f, 0x01, + 0xb0, 0x00, 0x80, 0x31, 0x77, 0x91, 0x81, 0x0b, 0xff, 0xbb, 0x08, 0x3a, 0x81, 0x7a, 0x86, 0x10, 0x6d, 0x7e, 0x26, 0x34, 0x2e, 0x2c, 0xb5, 0x62, 0x01, 0x07, 0x5c, 0x00, 0xb8, 0xfa, 0x43, 0x13, + 0xe7, 0x07, 0x03, 0x0f, 0x11, 0x2e, 0x2c, 0x37, 0x15, 0x00, 0x00, 0x00, 0xb1, 0x03, 0xec, 0x0b, 0x03, 0x83, 0xea, 0x1d, 0xbd, 0x6c, 0x09, 0x05, 0x56, 0xb6, 0x40, 0x1c, 0x93, 0x02, 0x07, 0x00, + 0xaa, 0x49, 0x06, 0x00, 0x0e, 0x00, 0x00, 0x00, 0x0e, 0x00, 0x00, 0x00, 0xf9, 0xff, 0xff, 0xff, 0x01, 0x00, 0x00, 0x00, 0xf5, 0xff, 0xff, 0xff, 0x07, 0x00, 0x00, 0x00, 0x90, 0xbe, 0xe4, 0x01, + 0x45, 0x00, 0x00, 0x00, 0x80, 0xa8, 0x12, 0x01, 0x6c, 0x00, 0x04, 0x00, 0x5c, 0x41, 0x4f, 0x21, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0xcb, 0xa3, 0xb5, 0x62, 0x01, 0x13, 0x1c, 0x00, + 0x00, 0x00, 0x00, 0x00, 0xb8, 0xfa, 0x43, 0x13, 0xec, 0x4c, 0x80, 0x19, 0x90, 0xe1, 0xc9, 0x03, 0xf7, 0x6c, 0xd9, 0x1b, 0x1c, 0xec, 0xf6, 0x00, 0xc8, 0x00, 0x00, 0x00, 0x63, 0xaa, 0xb5, 0x62, + 0x01, 0x11, 0x14, 0x00, 0xb8, 0xfa, 0x43, 0x13, 0x01, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x07, 0x00, 0x00, 0x00, 0x36, 0x6a, 0xb5, 0x62, 0x02, 0x13, 0x30, 0x00, + 0x03, 0x23, 0x00, 0x00, 0x0a, 0x09, 0x02, 0x00, 0xe4, 0x34, 0x90, 0x38, 0xf6, 0xe3, 0x08, 0x3a, 0xf9, 0x3f, 0x4e, 0x24, 0x5b, 0x00, 0xaf, 0x1b, 0x09, 0xfd, 0x5f, 0x04, 0xe6, 0xff, 0x93, 0x25, + 0x89, 0x97, 0x5f, 0x3b, 0x48, 0x09, 0x48, 0x0f, 0xf5, 0x7a, 0x58, 0x1f, 0x6d, 0xa0, 0x44, 0x25, 0x0e, 0x01, 0xb5, 0x62, 0x01, 0x35, 0x84, 0x02, 0xb8, 0xfa, 0x43, 0x13, 0x01, 0x35, 0x00, 0x00, + 0x00, 0x01, 0x27, 0x07, 0x00, 0x01, 0xf2, 0xff, 0x17, 0x19, 0x00, 0x00, 0x00, 0x07, 0x1a, 0x04, 0x1c, 0x01, 0x00, 0x00, 0x17, 0x19, 0x00, 0x00, 0x00, 0x08, 0x2e, 0x3e, 0x2e, 0x01, 0x02, 0x00, + 0x5f, 0x19, 0x32, 0x00, 0x00, 0x0a, 0x31, 0x40, 0x5f, 0x00, 0x05, 0x00, 0x5f, 0x19, 0x32, 0x00, 0x00, 0x0f, 0x00, 0x02, 0x18, 0x00, 0x00, 0x00, 0x11, 0x1a, 0x00, 0x00, 0x00, 0x10, 0x29, 0x23, + 0xc1, 0x00, 0xfa, 0xff, 0x5f, 0x19, 0x32, 0x00, 0x00, 0x12, 0x29, 0x0a, 0x46, 0x00, 0xec, 0xff, 0x17, 0x19, 0x00, 0x00, 0x00, 0x15, 0x2b, 0x21, 0x09, 0x01, 0xfd, 0xff, 0x5f, 0x19, 0x32, 0x00, + 0x00, 0x17, 0x2c, 0x25, 0x35, 0x00, 0xfa, 0xff, 0x5f, 0x19, 0x32, 0x00, 0x00, 0x1a, 0x09, 0x05, 0xaf, 0x00, 0x00, 0x00, 0x13, 0x19, 0x00, 0x00, 0x00, 0x1b, 0x2f, 0x50, 0x78, 0x00, 0x02, 0x00, + 0x5f, 0x19, 0x32, 0x00, 0x00, 0x1e, 0x26, 0x04, 0x3e, 0x01, 0x00, 0x00, 0x17, 0x1a, 0x00, 0x00, 0x00, 0x20, 0x27, 0x0a, 0x83, 0x00, 0x00, 0x00, 0x5f, 0x19, 0x32, 0x00, 0x01, 0x7b, 0x27, 0x1f, + 0x96, 0x00, 0x00, 0x00, 0x17, 0x1a, 0x00, 0x00, 0x01, 0x7f, 0x1f, 0x14, 0x7d, 0x00, 0x00, 0x00, 0x07, 0x1a, 0x00, 0x00, 0x01, 0x80, 0x00, 0x02, 0x66, 0x00, 0x00, 0x00, 0x00, 0x12, 0x00, 0x00, + 0x01, 0x88, 0x29, 0x23, 0xb9, 0x00, 0x00, 0x00, 0x17, 0x1a, 0x00, 0x00, 0x02, 0x01, 0x2c, 0x2f, 0xec, 0x00, 0x05, 0x00, 0x5f, 0x19, 0x32, 0x00, 0x02, 0x03, 0x25, 0x07, 0x1b, 0x00, 0x00, 0x00, + 0x17, 0x19, 0x00, 0x00, 0x02, 0x07, 0x26, 0x10, 0x7f, 0x00, 0xe1, 0xff, 0x1f, 0x19, 0x00, 0x00, 0x02, 0x08, 0x29, 0x17, 0x49, 0x00, 0xff, 0xff, 0x5f, 0x19, 0x32, 0x00, 0x02, 0x0d, 0x2a, 0x27, + 0x43, 0x00, 0x0b, 0x00, 0x5f, 0x19, 0x32, 0x00, 0x02, 0x15, 0x26, 0x14, 0xbb, 0x00, 0xfb, 0xff, 0x5f, 0x19, 0x32, 0x00, 0x02, 0x1a, 0x2d, 0x4d, 0x39, 0x01, 0x02, 0x00, 0x5f, 0x19, 0x32, 0x00, + 0x02, 0x1f, 0x2a, 0x1e, 0x35, 0x01, 0x07, 0x00, 0x5f, 0x19, 0x32, 0x00, 0x02, 0x21, 0x28, 0x1e, 0x08, 0x01, 0x01, 0x00, 0x5f, 0x19, 0x32, 0x00, 0x03, 0x02, 0x00, 0x02, 0x64, 0x00, 0x00, 0x00, + 0x10, 0x12, 0x00, 0x00, 0x03, 0x05, 0x00, 0x12, 0x78, 0x00, 0x00, 0x00, 0x10, 0x12, 0x00, 0x00, 0x03, 0x08, 0x20, 0x03, 0x2e, 0x00, 0x00, 0x00, 0x17, 0x1a, 0x00, 0x00, 0x03, 0x0d, 0x25, 0x0e, + 0x31, 0x00, 0x07, 0x00, 0x5f, 0x19, 0x32, 0x00, 0x03, 0x13, 0x00, 0x07, 0xb6, 0x00, 0x00, 0x00, 0x10, 0x12, 0x00, 0x00, 0x03, 0x14, 0x2d, 0x28, 0x8f, 0x00, 0xf7, 0xff, 0x1f, 0x19, 0x00, 0x00, + 0x03, 0x18, 0x00, 0x01, 0x55, 0x01, 0x00, 0x00, 0x10, 0x12, 0x00, 0x00, 0x03, 0x1a, 0x00, 0x13, 0x2c, 0x01, 0x00, 0x00, 0x10, 0x12, 0x00, 0x00, 0x03, 0x1d, 0x2f, 0x4c, 0x3f, 0x01, 0x03, 0x00, + 0x5f, 0x19, 0x32, 0x00, 0x03, 0x1e, 0x2d, 0x2a, 0x60, 0x00, 0xfd, 0xff, 0x5f, 0x19, 0x32, 0x00, 0x03, 0x20, 0x2d, 0x27, 0x43, 0x00, 0x04, 0x00, 0x5f, 0x19, 0x32, 0x00, 0x03, 0x23, 0x27, 0x16, + 0x20, 0x01, 0x00, 0x00, 0x27, 0x1a, 0x00, 0x00, 0x03, 0x27, 0x00, 0x03, 0x43, 0x00, 0x00, 0x00, 0x10, 0x12, 0x00, 0x00, 0x03, 0x29, 0x00, 0x04, 0x1c, 0x00, 0x00, 0x00, 0x10, 0x19, 0x00, 0x00, + 0x03, 0x2d, 0x28, 0x14, 0xf5, 0x00, 0xf9, 0xff, 0x1f, 0x19, 0x00, 0x00, 0x03, 0x3c, 0x00, 0x04, 0x67, 0x00, 0x00, 0x00, 0x10, 0x12, 0x00, 0x00, 0x05, 0x03, 0x00, 0xa5, 0x00, 0x00, 0x00, 0x00, + 0x01, 0x00, 0x00, 0x00, 0x06, 0x01, 0x26, 0x15, 0x99, 0x00, 0xea, 0xff, 0x5f, 0x19, 0x32, 0x00, 0x06, 0x07, 0x2b, 0x1b, 0x24, 0x00, 0xf6, 0xff, 0x5f, 0x19, 0x32, 0x00, 0x06, 0x08, 0x2d, 0x2c, + 0x5f, 0x00, 0xeb, 0xff, 0x5f, 0x19, 0x32, 0x00, 0x06, 0x0d, 0x1c, 0x0b, 0xd4, 0x00, 0xe1, 0xff, 0x5f, 0x19, 0x12, 0x00, 0x06, 0x0e, 0x2a, 0x24, 0x0c, 0x01, 0xdf, 0xff, 0x5f, 0x19, 0x32, 0x00, + 0x06, 0x0f, 0x2a, 0x16, 0x47, 0x01, 0x06, 0x00, 0x1f, 0x19, 0x00, 0x00, 0x06, 0x11, 0x24, 0x06, 0x19, 0x01, 0x00, 0x00, 0x17, 0x1a, 0x00, 0x00, 0x06, 0x16, 0x27, 0x07, 0x55, 0x00, 0x00, 0x00, + 0x17, 0x19, 0x00, 0x00, 0x06, 0x17, 0x2b, 0x38, 0x32, 0x00, 0xf8, 0xff, 0x5f, 0x19, 0x32, 0x00, 0x06, 0x18, 0x2e, 0x34, 0x34, 0x01, 0x06, 0x00, 0x5f, 0x19, 0x32, 0x00, 0x46, 0x49, 0xb5, 0x62, + 0x01, 0x43, 0x38, 0x05, 0xb8, 0xfa, 0x43, 0x13, 0x00, 0x53, 0x00, 0x00, 0x00, 0x01, 0x00, 0x00, 0xf2, 0xff, 0x27, 0x07, 0x00, 0x00, 0x01, 0x00, 0x01, 0x00, 0x00, 0x00, 0x00, 0x01, 0x03, 0x00, + 0xf7, 0xff, 0x24, 0x07, 0x00, 0x00, 0x01, 0x00, 0x01, 0x00, 0x00, 0x00, 0x00, 0x07, 0x00, 0x00, 0x00, 0x00, 0x1a, 0x07, 0x00, 0x00, 0x01, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x07, 0x03, 0x00, + 0x00, 0x00, 0x16, 0x04, 0x00, 0x00, 0x01, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x08, 0x00, 0x00, 0x02, 0x00, 0x2e, 0x07, 0x04, 0x00, 0xf9, 0x00, 0x01, 0x00, 0x00, 0x00, 0x00, 0x08, 0x03, 0x00, + 0x03, 0x00, 0x2c, 0x07, 0x04, 0x00, 0xf9, 0x00, 0x01, 0x00, 0x00, 0x00, 0x00, 0x0a, 0x00, 0x00, 0x05, 0x00, 0x31, 0x07, 0x04, 0x00, 0xf9, 0x00, 0x01, 0x00, 0x00, 0x00, 0x00, 0x0a, 0x03, 0x00, + 0xff, 0xff, 0x2b, 0x07, 0x04, 0x00, 0xf9, 0x00, 0x01, 0x00, 0x00, 0x00, 0x00, 0x0f, 0x00, 0x00, 0x00, 0x00, 0x00, 0x01, 0x00, 0x00, 0x01, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x0f, 0x04, 0x00, + 0x00, 0x00, 0x00, 0x01, 0x00, 0x00, 0x01, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x10, 0x00, 0x00, 0xfa, 0xff, 0x29, 0x07, 0x04, 0x00, 0xf9, 0x00, 0x01, 0x00, 0x00, 0x00, 0x00, 0x10, 0x04, 0x00, + 0x00, 0x00, 0x00, 0x01, 0x00, 0x00, 0x01, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x12, 0x03, 0x00, 0xe9, 0xff, 0x24, 0x07, 0x00, 0x00, 0x01, 0x00, 0x01, 0x00, 0x00, 0x00, 0x00, 0x12, 0x00, 0x00, + 0xec, 0xff, 0x29, 0x07, 0x00, 0x00, 0x01, 0x00, 0x01, 0x00, 0x00, 0x00, 0x00, 0x15, 0x00, 0x00, 0xfd, 0xff, 0x2b, 0x07, 0x04, 0x00, 0xf9, 0x00, 0x01, 0x00, 0x00, 0x00, 0x00, 0x15, 0x04, 0x00, + 0x00, 0x00, 0x00, 0x01, 0x00, 0x00, 0x01, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x17, 0x00, 0x00, 0xfa, 0xff, 0x2c, 0x07, 0x04, 0x00, 0xf9, 0x00, 0x01, 0x00, 0x00, 0x00, 0x00, 0x17, 0x03, 0x00, + 0xfa, 0xff, 0x2a, 0x07, 0x04, 0x00, 0xf9, 0x00, 0x01, 0x00, 0x00, 0x00, 0x00, 0x1a, 0x00, 0x00, 0x00, 0x00, 0x09, 0x03, 0x00, 0x00, 0x01, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x1a, 0x03, 0x00, + 0x00, 0x00, 0x0f, 0x04, 0x00, 0x00, 0x01, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x1b, 0x00, 0x00, 0x02, 0x00, 0x2f, 0x07, 0x04, 0x00, 0xf9, 0x00, 0x01, 0x00, 0x00, 0x00, 0x00, 0x1b, 0x03, 0x00, + 0x01, 0x00, 0x2b, 0x07, 0x04, 0x00, 0xe9, 0x00, 0x01, 0x00, 0x00, 0x00, 0x00, 0x1e, 0x00, 0x00, 0x00, 0x00, 0x26, 0x07, 0x00, 0x00, 0x01, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x1e, 0x03, 0x00, + 0x00, 0x00, 0x20, 0x07, 0x00, 0x00, 0x01, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x20, 0x00, 0x00, 0x00, 0x00, 0x27, 0x07, 0x04, 0x00, 0xf9, 0x00, 0x01, 0x00, 0x00, 0x00, 0x00, 0x20, 0x03, 0x00, + 0x08, 0x00, 0x24, 0x07, 0x04, 0x00, 0xf9, 0x00, 0x01, 0x00, 0x00, 0x00, 0x01, 0x7b, 0x00, 0x00, 0x00, 0x00, 0x27, 0x07, 0x00, 0x00, 0x01, 0x00, 0x00, 0x00, 0x00, 0x00, 0x01, 0x7f, 0x00, 0x00, + 0x00, 0x00, 0x1f, 0x07, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x01, 0x88, 0x00, 0x00, 0x00, 0x00, 0x29, 0x07, 0x00, 0x00, 0x01, 0x00, 0x00, 0x00, 0x00, 0x00, 0x02, 0x01, 0x00, 0x00, + 0x05, 0x00, 0x2c, 0x07, 0x04, 0x00, 0xf9, 0x00, 0x01, 0x00, 0x00, 0x00, 0x02, 0x01, 0x06, 0x00, 0x04, 0x00, 0x2f, 0x07, 0x04, 0x00, 0xf9, 0x00, 0x01, 0x00, 0x00, 0x00, 0x02, 0x03, 0x00, 0x00, + 0x00, 0x00, 0x25, 0x07, 0x00, 0x00, 0x01, 0x00, 0x00, 0x00, 0x00, 0x00, 0x02, 0x03, 0x06, 0x00, 0x00, 0x00, 0x27, 0x07, 0x00, 0x00, 0x01, 0x00, 0x00, 0x00, 0x00, 0x00, 0x02, 0x07, 0x00, 0x00, + 0xe1, 0xff, 0x26, 0x07, 0x00, 0x02, 0x21, 0x00, 0x01, 0x00, 0x00, 0x00, 0x02, 0x07, 0x06, 0x00, 0xd1, 0xff, 0x2a, 0x07, 0x00, 0x02, 0x21, 0x00, 0x01, 0x00, 0x00, 0x00, 0x02, 0x08, 0x00, 0x00, + 0xff, 0xff, 0x29, 0x07, 0x04, 0x00, 0xf9, 0x00, 0x01, 0x00, 0x00, 0x00, 0x02, 0x08, 0x06, 0x00, 0xfe, 0xff, 0x2a, 0x07, 0x04, 0x00, 0xf9, 0x00, 0x01, 0x00, 0x00, 0x00, 0x02, 0x0d, 0x00, 0x00, + 0x0b, 0x00, 0x2a, 0x07, 0x04, 0x00, 0xf9, 0x00, 0x01, 0x00, 0x00, 0x00, 0x02, 0x0d, 0x06, 0x00, 0x02, 0x00, 0x30, 0x07, 0x04, 0x00, 0xf9, 0x00, 0x01, 0x00, 0x00, 0x00, 0x02, 0x15, 0x00, 0x00, + 0xfb, 0xff, 0x26, 0x07, 0x04, 0x00, 0xf9, 0x00, 0x01, 0x00, 0x00, 0x00, 0x02, 0x15, 0x06, 0x00, 0x01, 0x00, 0x29, 0x07, 0x04, 0x00, 0xf9, 0x00, 0x01, 0x00, 0x00, 0x00, 0x02, 0x1a, 0x06, 0x00, + 0x01, 0x00, 0x31, 0x07, 0x04, 0x00, 0xf9, 0x00, 0x01, 0x00, 0x00, 0x00, 0x02, 0x1a, 0x00, 0x00, 0x02, 0x00, 0x2d, 0x07, 0x04, 0x00, 0xf9, 0x00, 0x01, 0x00, 0x00, 0x00, 0x02, 0x1f, 0x00, 0x00, + 0x07, 0x00, 0x2a, 0x07, 0x04, 0x00, 0xf9, 0x00, 0x01, 0x00, 0x00, 0x00, 0x02, 0x1f, 0x06, 0x00, 0x02, 0x00, 0x2e, 0x07, 0x04, 0x00, 0xf9, 0x00, 0x01, 0x00, 0x00, 0x00, 0x02, 0x21, 0x00, 0x00, + 0x01, 0x00, 0x28, 0x07, 0x04, 0x00, 0xf9, 0x00, 0x01, 0x00, 0x00, 0x00, 0x02, 0x21, 0x06, 0x00, 0x0a, 0x00, 0x2f, 0x07, 0x04, 0x00, 0xf9, 0x00, 0x01, 0x00, 0x00, 0x00, 0x03, 0x08, 0x00, 0x00, + 0x00, 0x00, 0x20, 0x07, 0x00, 0x00, 0x01, 0x00, 0x00, 0x00, 0x00, 0x00, 0x03, 0x08, 0x02, 0x00, 0x00, 0x00, 0x24, 0x07, 0x00, 0x00, 0x01, 0x00, 0x00, 0x00, 0x00, 0x00, 0x03, 0x0d, 0x02, 0x00, + 0x1c, 0x00, 0x28, 0x07, 0x04, 0x00, 0x69, 0x00, 0x01, 0x00, 0x00, 0x00, 0x03, 0x0d, 0x00, 0x00, 0x07, 0x00, 0x25, 0x07, 0x04, 0x00, 0xf9, 0x00, 0x01, 0x00, 0x00, 0x00, 0x03, 0x14, 0x00, 0x00, + 0xf7, 0xff, 0x2d, 0x07, 0x00, 0x02, 0x21, 0x00, 0x01, 0x00, 0x00, 0x00, 0x03, 0x14, 0x02, 0x00, 0x00, 0x00, 0x00, 0x01, 0x00, 0x00, 0x01, 0x00, 0x00, 0x00, 0x00, 0x00, 0x03, 0x1a, 0x02, 0x00, + 0x00, 0x00, 0x00, 0x01, 0x00, 0x00, 0x01, 0x00, 0x00, 0x00, 0x00, 0x00, 0x03, 0x1d, 0x00, 0x00, 0x03, 0x00, 0x2f, 0x07, 0x04, 0x00, 0xf9, 0x00, 0x01, 0x00, 0x00, 0x00, 0x03, 0x1d, 0x02, 0x00, + 0x00, 0x00, 0x00, 0x01, 0x00, 0x00, 0x01, 0x00, 0x00, 0x00, 0x00, 0x00, 0x03, 0x1e, 0x00, 0x00, 0xfd, 0xff, 0x2d, 0x07, 0x04, 0x00, 0xf9, 0x00, 0x01, 0x00, 0x00, 0x00, 0x03, 0x1e, 0x02, 0x00, + 0x00, 0x00, 0x00, 0x01, 0x00, 0x00, 0x01, 0x00, 0x00, 0x00, 0x00, 0x00, 0x03, 0x20, 0x00, 0x00, 0x04, 0x00, 0x2d, 0x07, 0x04, 0x00, 0xf9, 0x00, 0x01, 0x00, 0x00, 0x00, 0x03, 0x20, 0x02, 0x00, + 0x00, 0x00, 0x00, 0x01, 0x00, 0x00, 0x01, 0x00, 0x00, 0x00, 0x00, 0x00, 0x03, 0x23, 0x00, 0x00, 0x00, 0x00, 0x27, 0x07, 0x00, 0x00, 0x02, 0x00, 0x00, 0x00, 0x00, 0x00, 0x03, 0x2d, 0x00, 0x00, + 0xf9, 0xff, 0x28, 0x07, 0x00, 0x02, 0x21, 0x00, 0x01, 0x00, 0x00, 0x00, 0x03, 0x2d, 0x02, 0x00, 0x00, 0x00, 0x00, 0x01, 0x00, 0x00, 0x01, 0x00, 0x00, 0x00, 0x00, 0x00, 0x05, 0x03, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x01, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x06, 0x01, 0x00, 0x08, 0xea, 0xff, 0x26, 0x07, 0x04, 0x00, 0xf9, 0x00, 0x01, 0x00, 0x00, 0x00, 0x06, 0x01, 0x02, 0x08, + 0x11, 0x00, 0x22, 0x07, 0x04, 0x00, 0x69, 0x00, 0x01, 0x00, 0x00, 0x00, 0x06, 0x07, 0x00, 0x0c, 0xf6, 0xff, 0x2b, 0x07, 0x04, 0x00, 0xf9, 0x00, 0x01, 0x00, 0x00, 0x00, 0x06, 0x07, 0x02, 0x0c, + 0xf9, 0xff, 0x27, 0x07, 0x04, 0x00, 0xf9, 0x00, 0x01, 0x00, 0x00, 0x00, 0x06, 0x08, 0x00, 0x0d, 0xeb, 0xff, 0x2d, 0x07, 0x04, 0x00, 0xf9, 0x00, 0x01, 0x00, 0x00, 0x00, 0x06, 0x08, 0x02, 0x0d, + 0xf3, 0xff, 0x2a, 0x07, 0x04, 0x00, 0xf9, 0x00, 0x01, 0x00, 0x00, 0x00, 0x06, 0x0d, 0x00, 0x05, 0xe1, 0xff, 0x1c, 0x07, 0x04, 0x00, 0x69, 0x00, 0x01, 0x00, 0x00, 0x00, 0x06, 0x0d, 0x02, 0x05, + 0xf3, 0xff, 0x20, 0x07, 0x04, 0x00, 0xf9, 0x00, 0x01, 0x00, 0x00, 0x00, 0x06, 0x0e, 0x00, 0x00, 0xdf, 0xff, 0x2a, 0x07, 0x04, 0x00, 0xf9, 0x00, 0x01, 0x00, 0x00, 0x00, 0x06, 0x0e, 0x02, 0x00, + 0xf5, 0xff, 0x2a, 0x07, 0x04, 0x00, 0xe9, 0x00, 0x01, 0x00, 0x00, 0x00, 0x06, 0x0f, 0x00, 0x07, 0x06, 0x00, 0x2a, 0x07, 0x00, 0x02, 0x21, 0x00, 0x01, 0x00, 0x00, 0x00, 0x06, 0x0f, 0x02, 0x07, + 0x0d, 0x00, 0x29, 0x07, 0x00, 0x02, 0x21, 0x00, 0x01, 0x00, 0x00, 0x00, 0x06, 0x11, 0x00, 0x0b, 0x00, 0x00, 0x24, 0x07, 0x00, 0x00, 0x01, 0x00, 0x00, 0x00, 0x00, 0x00, 0x06, 0x16, 0x00, 0x04, + 0x00, 0x00, 0x27, 0x07, 0x00, 0x00, 0x01, 0x00, 0x00, 0x00, 0x00, 0x00, 0x06, 0x16, 0x02, 0x04, 0x00, 0x00, 0x27, 0x07, 0x00, 0x00, 0x01, 0x00, 0x00, 0x00, 0x00, 0x00, 0x06, 0x17, 0x00, 0x0a, + 0xf8, 0xff, 0x2b, 0x07, 0x04, 0x00, 0xf9, 0x00, 0x01, 0x00, 0x00, 0x00, 0x06, 0x17, 0x02, 0x0a, 0x00, 0x00, 0x00, 0x01, 0x00, 0x00, 0x01, 0x00, 0x00, 0x00, 0x00, 0x00, 0x06, 0x18, 0x00, 0x09, + 0x06, 0x00, 0x2e, 0x07, 0x04, 0x00, 0xf9, 0x00, 0x01, 0x00, 0x00, 0x00, 0x06, 0x18, 0x02, 0x09, 0xf9, 0xff, 0x2c, 0x07, 0x04, 0x00, 0xf9, 0x00, 0x01, 0x00, 0x00, 0x00, 0xb0, 0xdd, 0xb5, 0x62, + 0x01, 0x03, 0x10, 0x00, 0xb8, 0xfa, 0x43, 0x13, 0x03, 0xdf, 0x03, 0x88, 0xf2, 0x13, 0x17, 0x00, 0xd5, 0x75, 0xb1, 0x00, 0xa0, 0x87, 0xb5, 0x62, 0x01, 0x20, 0x10, 0x00, 0xb8, 0xfa, 0x43, 0x13, + 0xb1, 0x41, 0x00, 0x00, 0xcd, 0x08, 0x12, 0x07, 0x01, 0x00, 0x00, 0x00, 0x1a, 0xa5, 0xb5, 0x62, 0x01, 0x22, 0x14, 0x00, 0xb8, 0xfa, 0x43, 0x13, 0x8f, 0x00, 0x0f, 0x00, 0x0a, 0x01, 0x00, 0x00, + 0x01, 0x00, 0x00, 0x00, 0x7d, 0x00, 0x00, 0x00, 0x66, 0x06, 0xb5, 0x62, 0x01, 0x36, 0x40, 0x00, 0xb8, 0xfa, 0x43, 0x13, 0x00, 0x01, 0x01, 0x00, 0x32, 0x30, 0x19, 0x40, 0x00, 0x00, 0x80, 0x3f, + 0x2e, 0x8e, 0x69, 0x38, 0x88, 0x21, 0xad, 0xb6, 0x08, 0xd0, 0xf5, 0x37, 0x6d, 0x9e, 0x00, 0x38, 0x3b, 0xf0, 0xc3, 0xb5, 0x96, 0x61, 0x52, 0x39, 0xa9, 0x3c, 0x91, 0x3b, 0x58, 0x71, 0xe4, 0xb8, + 0xb0, 0xc8, 0xb1, 0x39, 0x32, 0xfd, 0x05, 0x3b, 0x3c, 0xb1, 0x01, 0xb9, 0x3a, 0xe5, 0x8f, 0x3b, 0x47, 0x29, 0xb5, 0x62, 0x01, 0x3c, 0x40, 0x00, 0x01, 0x00, 0x00, 0x00, 0xb8, 0xfa, 0x43, 0x13, + 0xb8, 0xd6, 0x24, 0x00, 0x22, 0xb1, 0x09, 0x00, 0x85, 0x3a, 0x00, 0x00, 0xd1, 0x17, 0x26, 0x00, 0xcd, 0x7d, 0x16, 0x00, 0x00, 0x00, 0x00, 0x00, 0x4e, 0x4e, 0x40, 0x3b, 0x64, 0x00, 0x00, 0x00, + 0x64, 0x00, 0x00, 0x00, 0x8e, 0x00, 0x00, 0x00, 0x64, 0x00, 0x00, 0x00, 0x02, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x17, 0x01, 0x00, 0x00, 0x2c, 0x10, 0xb5, 0x62, 0x01, 0x61, 0x04, 0x00, + 0xb8, 0xfa, 0x43, 0x13, 0x6e, 0x2e +}; diff --git a/fpsdk_common/test/gnss_test.cpp b/fpsdk_common/test/gnss_test.cpp new file mode 100644 index 0000000..afba5e0 --- /dev/null +++ b/fpsdk_common/test/gnss_test.cpp @@ -0,0 +1,221 @@ +/** + * \verbatim + * ___ ___ + * \ \ / / + * \ \/ / Copyright (c) Fixposition AG (www.fixposition.com) and contributors + * / /\ \ License: see the LICENSE file + * /__/ \__\ + * \endverbatim + * + * @file + * @brief Fixposition SDK: tests for fpsdk::common::gnss + */ + +/* LIBC/STL */ + +/* EXTERNAL */ +#include + +/* PACKAGE */ +#include +#include + +namespace { +/* ****************************************************************************************************************** */ +using namespace fpsdk::common::gnss; + +TEST(GnssTest, GnssFixTypeStr) +{ + // clang-format off + EXPECT_EQ(std::string(GnssFixTypeStr(GnssFixType::UNKNOWN)), std::string("UNKNOWN")); + EXPECT_EQ(std::string(GnssFixTypeStr(GnssFixType::NOFIX)), std::string("NOFIX")); + EXPECT_EQ(std::string(GnssFixTypeStr(GnssFixType::DRONLY)), std::string("DRONLY")); + EXPECT_EQ(std::string(GnssFixTypeStr(GnssFixType::TIME)), std::string("TIME")); + EXPECT_EQ(std::string(GnssFixTypeStr(GnssFixType::SPP_2D)), std::string("SPP_2D")); + EXPECT_EQ(std::string(GnssFixTypeStr(GnssFixType::SPP_3D)), std::string("SPP_3D")); + EXPECT_EQ(std::string(GnssFixTypeStr(GnssFixType::SPP_3D_DR)), std::string("SPP_3D_DR")); + EXPECT_EQ(std::string(GnssFixTypeStr(GnssFixType::RTK_FLOAT)), std::string("RTK_FLOAT")); + EXPECT_EQ(std::string(GnssFixTypeStr(GnssFixType::RTK_FIXED)), std::string("RTK_FIXED")); + EXPECT_EQ(std::string(GnssFixTypeStr(GnssFixType::RTK_FLOAT_DR)), std::string("RTK_FLOAT_DR")); + EXPECT_EQ(std::string(GnssFixTypeStr(GnssFixType::RTK_FIXED_DR)), std::string("RTK_FIXED_DR")); + EXPECT_EQ(std::string(GnssFixTypeStr((GnssFixType)99)), std::string("?")); + // clang-format on +} + +// --------------------------------------------------------------------------------------------------------------------- + +TEST(GnssTest, GnssStr) +{ + // clang-format off + EXPECT_EQ(std::string(GnssStr(Gnss::UNKNOWN)), std::string("UNKNOWN")); + EXPECT_EQ(std::string(GnssStr(Gnss::GPS)), std::string("GPS")); + EXPECT_EQ(std::string(GnssStr(Gnss::SBAS)), std::string("SBAS")); + EXPECT_EQ(std::string(GnssStr(Gnss::GAL)), std::string("GAL")); + EXPECT_EQ(std::string(GnssStr(Gnss::BDS)), std::string("BDS")); + EXPECT_EQ(std::string(GnssStr(Gnss::QZSS)), std::string("QZSS")); + EXPECT_EQ(std::string(GnssStr(Gnss::GLO)), std::string("GLO")); + EXPECT_EQ(std::string(GnssStr(Gnss::NAVIC)), std::string("NAVIC")); + EXPECT_EQ(std::string(GnssStr((Gnss)99)), std::string("?")); + // clang-format on +} + +// --------------------------------------------------------------------------------------------------------------------- + +TEST(GnssTest, SignalStr) +{ + // clang-format off + EXPECT_EQ(std::string(SignalStr(Signal::UNKNOWN)), std::string("UNKNOWN")); + EXPECT_EQ(std::string(SignalStr(Signal::BDS_B1C)), std::string("BDS_B1C")); + EXPECT_EQ(std::string(SignalStr(Signal::BDS_B1I)), std::string("BDS_B1I")); + EXPECT_EQ(std::string(SignalStr(Signal::BDS_B2A)), std::string("BDS_B2A")); + EXPECT_EQ(std::string(SignalStr(Signal::BDS_B2I)), std::string("BDS_B2I")); + EXPECT_EQ(std::string(SignalStr(Signal::GAL_E1)), std::string("GAL_E1")); + EXPECT_EQ(std::string(SignalStr(Signal::GAL_E5A)), std::string("GAL_E5A")); + EXPECT_EQ(std::string(SignalStr(Signal::GAL_E5B)), std::string("GAL_E5B")); + EXPECT_EQ(std::string(SignalStr(Signal::GLO_L1OF)), std::string("GLO_L1OF")); + EXPECT_EQ(std::string(SignalStr(Signal::GLO_L2OF)), std::string("GLO_L2OF")); + EXPECT_EQ(std::string(SignalStr(Signal::GPS_L1CA)), std::string("GPS_L1CA")); + EXPECT_EQ(std::string(SignalStr(Signal::GPS_L2C)), std::string("GPS_L2C")); + EXPECT_EQ(std::string(SignalStr(Signal::GPS_L5)), std::string("GPS_L5")); + EXPECT_EQ(std::string(SignalStr(Signal::QZSS_L1CA)), std::string("QZSS_L1CA")); + EXPECT_EQ(std::string(SignalStr(Signal::QZSS_L1S)), std::string("QZSS_L1S")); + EXPECT_EQ(std::string(SignalStr(Signal::QZSS_L2C)), std::string("QZSS_L2C")); + EXPECT_EQ(std::string(SignalStr(Signal::QZSS_L5)), std::string("QZSS_L5")); + EXPECT_EQ(std::string(SignalStr(Signal::SBAS_L1CA)), std::string("SBAS_L1CA")); + EXPECT_EQ(std::string(SignalStr(Signal::NAVIC_L5A)), std::string("NAVIC_L5A")); + EXPECT_EQ(std::string(SignalStr((Signal)99)), std::string("?")); + // clang-format on +} + +// --------------------------------------------------------------------------------------------------------------------- + +TEST(GnssTest, BandStr) +{ + // clang-format off + EXPECT_EQ(std::string(BandStr(Band::UNKNOWN)), std::string("UNKNOWN")); + EXPECT_EQ(std::string(BandStr(Band::L1)), std::string("L1")); + EXPECT_EQ(std::string(BandStr(Band::L2)), std::string("L2")); + EXPECT_EQ(std::string(BandStr(Band::L5)), std::string("L5")); + EXPECT_EQ(std::string(BandStr((Band)99)), std::string("?")); + // clang-format on +} + +// --------------------------------------------------------------------------------------------------------------------- + +TEST(GnssTest, Sat) +{ + const Sat sat = GnssSvNrToSat(Gnss::GPS, 12); + DEBUG("sat=%04x %02x %02x", sat, (int)SatToGnss(sat), (int)SatToSvNr(sat)); + EXPECT_NE(sat, INVALID_SAT); + EXPECT_EQ(SatToGnss(sat), Gnss::GPS); + EXPECT_EQ(SatToSvNr(sat), 12); +} + +// --------------------------------------------------------------------------------------------------------------------- + +TEST(GnssTest, SatSig) +{ + const SatSig satsig = GnssSvNrBandSignalToSatSig(Gnss::GPS, 12, Band::L1, Signal::GPS_L1CA); + DEBUG("satsig=%08x %02x %02x %02x %02x", satsig, (int)SatSigToGnss(satsig), (int)SatSigToSvNr(satsig), + (int)SatSigToBand(satsig), (int)SatSigToSignal(satsig)); + EXPECT_NE(satsig, INVALID_SATSIG); + EXPECT_EQ(SatSigToGnss(satsig), Gnss::GPS); + EXPECT_EQ(SatSigToSvNr(satsig), 12); + EXPECT_EQ(SatSigToBand(satsig), Band::L1); + EXPECT_EQ(SatSigToSignal(satsig), Signal::GPS_L1CA); +} + +// --------------------------------------------------------------------------------------------------------------------- + +TEST(GnssTest, SatStr) +{ + // Valid + EXPECT_EQ(std::string(SatStr(GnssSvNrToSat(Gnss::GPS, 1))), std::string("G01")); + EXPECT_EQ(std::string(SatStr(GnssSvNrToSat(Gnss::SBAS, 22))), std::string("S22")); + EXPECT_EQ(std::string(SatStr(GnssSvNrToSat(Gnss::GAL, 12))), std::string("E12")); + EXPECT_EQ(std::string(SatStr(GnssSvNrToSat(Gnss::BDS, 5))), std::string("C05")); + EXPECT_EQ(std::string(SatStr(GnssSvNrToSat(Gnss::QZSS, 9))), std::string("J09")); + EXPECT_EQ(std::string(SatStr(GnssSvNrToSat(Gnss::GLO, 15))), std::string("R15")); + + // Invalid + EXPECT_EQ(std::string(SatStr(GnssSvNrToSat(Gnss::GPS, 0))), std::string("G??")); + EXPECT_EQ(std::string(SatStr(GnssSvNrToSat(Gnss::GPS, 33))), std::string("G??")); + EXPECT_EQ(std::string(SatStr(GnssSvNrToSat(Gnss::SBAS, 19))), std::string("S??")); + EXPECT_EQ(std::string(SatStr(GnssSvNrToSat(Gnss::SBAS, 59))), std::string("S??")); + EXPECT_EQ(std::string(SatStr(GnssSvNrToSat(Gnss::GAL, 37))), std::string("E??")); + EXPECT_EQ(std::string(SatStr(GnssSvNrToSat(Gnss::BDS, 64))), std::string("C??")); + EXPECT_EQ(std::string(SatStr(GnssSvNrToSat(Gnss::QZSS, 11))), std::string("J??")); + EXPECT_EQ(std::string(SatStr(GnssSvNrToSat(Gnss::GLO, 33))), std::string("R??")); + EXPECT_EQ(std::string(SatStr(GnssSvNrToSat(Gnss::UNKNOWN, 12))), std::string("???")); +} + +// --------------------------------------------------------------------------------------------------------------------- + +TEST(GnssTest, StrSat) +{ + // Valid + EXPECT_EQ(StrSat("G01"), GnssSvNrToSat(Gnss::GPS, 1)); + EXPECT_EQ(StrSat("S22"), GnssSvNrToSat(Gnss::SBAS, 22)); + EXPECT_EQ(StrSat("E12"), GnssSvNrToSat(Gnss::GAL, 12)); + EXPECT_EQ(StrSat("C05"), GnssSvNrToSat(Gnss::BDS, 5)); + EXPECT_EQ(StrSat("J09"), GnssSvNrToSat(Gnss::QZSS, 9)); + EXPECT_EQ(StrSat("R15"), GnssSvNrToSat(Gnss::GLO, 15)); + + // Invalid + EXPECT_EQ(StrSat("G00"), INVALID_SAT); + EXPECT_EQ(StrSat("G33"), INVALID_SAT); + EXPECT_EQ(StrSat("S19"), INVALID_SAT); + EXPECT_EQ(StrSat("S59"), INVALID_SAT); + EXPECT_EQ(StrSat("E37"), INVALID_SAT); + EXPECT_EQ(StrSat("C64"), INVALID_SAT); + EXPECT_EQ(StrSat("J11"), INVALID_SAT); + EXPECT_EQ(StrSat("R33"), INVALID_SAT); + EXPECT_EQ(StrSat("gugugs"), INVALID_SAT); + EXPECT_EQ(StrSat(""), INVALID_SAT); + EXPECT_EQ(StrSat("G1"), INVALID_SAT); + EXPECT_EQ(StrSat("E1"), INVALID_SAT); + EXPECT_EQ(StrSat("C1"), INVALID_SAT); + EXPECT_EQ(StrSat("J1"), INVALID_SAT); + EXPECT_EQ(StrSat("R1"), INVALID_SAT); +} + +// --------------------------------------------------------------------------------------------------------------------- + +TEST(GnssTest, UbxGnssIdToGnss) +{ + EXPECT_EQ(UbxGnssIdToGnss(0), Gnss::GPS); + EXPECT_EQ(UbxGnssIdToGnss(2), Gnss::GAL); +} + +// --------------------------------------------------------------------------------------------------------------------- + +TEST(GnssTest, UbxGnssIdSvIdToSat) +{ + EXPECT_EQ(UbxGnssIdSvIdToSat(0, 12), GnssSvNrToSat(Gnss::GPS, 12)); + EXPECT_EQ(UbxGnssIdSvIdToSat(2, 1), GnssSvNrToSat(Gnss::GAL, 1)); +} + +// --------------------------------------------------------------------------------------------------------------------- + +TEST(GnssTest, UbxGnssIdSigIdToSignal) +{ + EXPECT_EQ(UbxGnssIdSigIdToSignal(0, 0), Signal::GPS_L1CA); + EXPECT_EQ(UbxGnssIdSigIdToSignal(2, 5), Signal::GAL_E5B); // E5 bI + EXPECT_EQ(UbxGnssIdSigIdToSignal(2, 6), Signal::GAL_E5B); // E5 bQ +} + +/* ****************************************************************************************************************** */ +} // namespace + +int main(int argc, char** argv) +{ + testing::InitGoogleTest(&argc, argv); + auto level = fpsdk::common::logging::LoggingLevel::WARNING; + for (int ix = 0; ix < argc; ix++) { + if ((argv[ix][0] == '-') && argv[ix][1] == 'v') { + level++; + } + } + fpsdk::common::logging::LoggingSetParams(level); + return RUN_ALL_TESTS(); +} diff --git a/fpsdk_common/test/parser_crc_test.cpp b/fpsdk_common/test/parser_crc_test.cpp new file mode 100644 index 0000000..4a49168 --- /dev/null +++ b/fpsdk_common/test/parser_crc_test.cpp @@ -0,0 +1,358 @@ +/** + * \verbatim + * ___ ___ + * \ \ / / + * \ \/ / Copyright (c) Fixposition AG (www.fixposition.com) and contributors + * / /\ \ License: see the LICENSE file + * /__/ \__\ + * \endverbatim + * + * @file + * @brief Fixposition SDK: tests for fpsdk::common::parser::crc + */ + +/* LIBC/STL */ +#include + +/* EXTERNAL */ +#include + +/* PACKAGE */ +#include +#include + +namespace { +/* ****************************************************************************************************************** */ +using namespace fpsdk::common::parser::crc; + +static const uint8_t RANDOM_1_BYTE[] = { 0xb1 }; +static const uint8_t RANDOM_2_BYTES[] = { 0x32, 0x43 }; +static const uint8_t RANDOM_3_BYTES[] = { 0x13, 0xd3, 0xe8 }; +static const uint8_t RANDOM_4_BYTES[] = { 0xc4, 0xd2, 0xee, 0xac }; +static const uint8_t RANDOM_5_BYTES[] = { 0x6d, 0xb3, 0x5b, 0xc6, 0xe1 }; +static const uint8_t RANDOM_6_BYTES[] = { 0x85, 0xb5, 0xaf, 0xf8, 0x00, 0x89 }; +static const uint8_t RANDOM_7_BYTES[] = { 0x1b, 0xa7, 0x24, 0xc3, 0x3a, 0xb7, 0x77 }; +static const uint8_t RANDOM_8_BYTES[] = { 0x25, 0x49, 0xfe, 0x66, 0x14, 0xb1, 0x86, 0x4d }; +static const uint8_t RANDOM_9_BYTES[] = { 0x36, 0x6b, 0x6b, 0x4a, 0xa7, 0xfb, 0xdd, 0xa9, 0xc2 }; +static const uint8_t RANDOM_10_BYTES[] = { 0x62, 0x61, 0x73, 0xb8, 0xa8, 0xc4, 0x89, 0xda, 0xc9, 0xcc }; +static const uint8_t RANDOM_11_BYTES[] = { 0x7f, 0xe8, 0x33, 0x74, 0xd4, 0xab, 0x8a, 0xb0, 0xf7, 0xd8, 0x8d }; +static const uint8_t RANDOM_12_BYTES[] = { 0x1a, 0x48, 0x8a, 0xe1, 0xa9, 0xf7, 0x15, 0xce, 0x62, 0xf3, 0xd5, 0x21 }; +static const uint8_t RANDOM_13_BYTES[] = { 0xb4, 0xa9, 0x71, 0x80, 0x60, 0x7f, 0xec, 0xa1, 0x87, 0x94, 0xe0, 0x77, + 0x6a }; +static const uint8_t RANDOM_14_BYTES[] = { 0xca, 0x5b, 0x01, 0xb4, 0x21, 0xb9, 0xd8, 0xea, 0xa7, 0x4b, 0xb0, 0xfa, 0xaf, + 0xc6 }; +static const uint8_t RANDOM_15_BYTES[] = { 0x4c, 0x7b, 0xe8, 0x14, 0x68, 0x23, 0x85, 0x4f, 0xf6, 0x10, 0x27, 0x6e, 0x6c, + 0x6d, 0x85 }; +static const uint8_t RANDOM_16_BYTES[] = { 0x4c, 0x7b, 0xe8, 0x14, 0x68, 0x23, 0x85, 0x4f, 0xf6, 0x10, 0x27, 0x6e, 0x6c, + 0x6d, 0x85, 0x66 }; +static const uint8_t RANDOM_29_BYTES[] = { 0x63, 0xe1, 0x7a, 0x23, 0x21, 0x5e, 0x0d, 0x54, 0x90, 0x77, 0xfe, 0xda, 0x12, + 0x20, 0x63, 0x03, 0x93, 0xe8, 0x1f, 0x65, 0x2c, 0x07, 0x4b, 0x9a, 0x8d, 0x10, 0x46, 0xc6, 0x61 }; +static const uint8_t RANDOM_30_BYTES[] = { 0xd6, 0xda, 0x6b, 0xf8, 0x53, 0xc1, 0x35, 0xfa, 0xbe, 0x9e, 0x30, 0xc9, 0x48, + 0x57, 0x25, 0xde, 0x88, 0x74, 0x9e, 0x97, 0x3d, 0x42, 0x0e, 0xfa, 0xf1, 0x9e, 0x0d, 0xa8, 0x65, 0x5d }; +static const uint8_t RANDOM_31_BYTES[] = { 0xe2, 0xe9, 0xea, 0x65, 0x49, 0xd5, 0xee, 0x9d, 0xba, 0x63, 0x6a, 0xbb, 0x17, + 0xb8, 0x5b, 0x90, 0xb8, 0xcc, 0xb7, 0x44, 0x71, 0x09, 0xa7, 0xc4, 0x8c, 0xf5, 0x69, 0xbe, 0x64, 0x68, 0xdf }; +static const uint8_t RANDOM_32_BYTES[] = { 0xe4, 0x97, 0x5f, 0x0d, 0x23, 0x44, 0xb3, 0xf0, 0x14, 0x07, 0x17, 0xe6, 0x16, + 0x2e, 0xc6, 0xfd, 0x40, 0xff, 0x76, 0x47, 0xd7, 0xaa, 0xdf, 0xb8, 0x7d, 0x60, 0xe8, 0x75, 0x50, 0x49, 0x8f, 0xcf }; +static const uint8_t RANDOM_64_BYTES[] = { 0xfc, 0xf3, 0xbb, 0x2b, 0x6f, 0xf0, 0x77, 0xc9, 0x03, 0x5f, 0x43, 0xb3, 0xc6, + 0xb3, 0x51, 0xbf, 0xbb, 0x44, 0x3d, 0x11, 0x58, 0xf1, 0x47, 0x1d, 0xcc, 0xa8, 0x3f, 0x87, 0x33, 0x50, 0x57, 0xe0, + 0xf8, 0xa0, 0x4d, 0x88, 0x82, 0x7a, 0xd6, 0x5c, 0x56, 0x72, 0x28, 0xa0, 0x82, 0x7f, 0xba, 0xfa, 0xaf, 0x2a, 0x61, + 0xed, 0xfa, 0x60, 0xa4, 0xa6, 0x27, 0x07, 0xe9, 0x5b, 0x32, 0xd1, 0xb7, 0x9a }; + +// --------------------------------------------------------------------------------------------------------------------- + +TEST(CrcTest, Data) +{ + EXPECT_EQ(sizeof(RANDOM_1_BYTE), (size_t)1); + EXPECT_EQ(sizeof(RANDOM_2_BYTES), (size_t)2); + EXPECT_EQ(sizeof(RANDOM_3_BYTES), (size_t)3); + EXPECT_EQ(sizeof(RANDOM_4_BYTES), (size_t)4); + EXPECT_EQ(sizeof(RANDOM_5_BYTES), (size_t)5); + EXPECT_EQ(sizeof(RANDOM_6_BYTES), (size_t)6); + EXPECT_EQ(sizeof(RANDOM_7_BYTES), (size_t)7); + EXPECT_EQ(sizeof(RANDOM_8_BYTES), (size_t)8); + EXPECT_EQ(sizeof(RANDOM_9_BYTES), (size_t)9); + EXPECT_EQ(sizeof(RANDOM_10_BYTES), (size_t)10); + EXPECT_EQ(sizeof(RANDOM_11_BYTES), (size_t)11); + EXPECT_EQ(sizeof(RANDOM_12_BYTES), (size_t)12); + EXPECT_EQ(sizeof(RANDOM_13_BYTES), (size_t)13); + EXPECT_EQ(sizeof(RANDOM_14_BYTES), (size_t)14); + EXPECT_EQ(sizeof(RANDOM_15_BYTES), (size_t)15); + EXPECT_EQ(sizeof(RANDOM_16_BYTES), (size_t)16); + EXPECT_EQ(sizeof(RANDOM_29_BYTES), (size_t)29); + EXPECT_EQ(sizeof(RANDOM_30_BYTES), (size_t)30); + EXPECT_EQ(sizeof(RANDOM_31_BYTES), (size_t)31); + EXPECT_EQ(sizeof(RANDOM_32_BYTES), (size_t)32); + EXPECT_EQ(sizeof(RANDOM_64_BYTES), (size_t)64); +} + +// --------------------------------------------------------------------------------------------------------------------- + +TEST(CrcTest, Crc32fpb) +{ + // Bad input should lead to 0 CRC + EXPECT_EQ(Crc32fpb(NULL, 0), (uint32_t)0x00000000); + EXPECT_EQ(Crc32fpb(NULL, 1), (uint32_t)0x00000000); + EXPECT_EQ(Crc32fpb(RANDOM_64_BYTES, 0), (uint32_t)0x00000000); + // Actual data + EXPECT_EQ(Crc32fpb(RANDOM_1_BYTE, sizeof(RANDOM_1_BYTE)), (uint32_t)0x3243baa7); + EXPECT_EQ(Crc32fpb(RANDOM_2_BYTES, sizeof(RANDOM_2_BYTES)), (uint32_t)0xc8e898ff); + EXPECT_EQ(Crc32fpb(RANDOM_3_BYTES, sizeof(RANDOM_3_BYTES)), (uint32_t)0x9301f69e); + EXPECT_EQ(Crc32fpb(RANDOM_4_BYTES, sizeof(RANDOM_4_BYTES)), (uint32_t)0x7b42e10b); + EXPECT_EQ(Crc32fpb(RANDOM_5_BYTES, sizeof(RANDOM_5_BYTES)), (uint32_t)0x708c17e9); + EXPECT_EQ(Crc32fpb(RANDOM_6_BYTES, sizeof(RANDOM_6_BYTES)), (uint32_t)0xaa9195ba); + EXPECT_EQ(Crc32fpb(RANDOM_7_BYTES, sizeof(RANDOM_7_BYTES)), (uint32_t)0x7de7be0d); + EXPECT_EQ(Crc32fpb(RANDOM_8_BYTES, sizeof(RANDOM_8_BYTES)), (uint32_t)0xd91fc4f1); + EXPECT_EQ(Crc32fpb(RANDOM_9_BYTES, sizeof(RANDOM_9_BYTES)), (uint32_t)0xd4b803fc); + EXPECT_EQ(Crc32fpb(RANDOM_10_BYTES, sizeof(RANDOM_10_BYTES)), (uint32_t)0xbb8e4f8d); + EXPECT_EQ(Crc32fpb(RANDOM_11_BYTES, sizeof(RANDOM_11_BYTES)), (uint32_t)0x19082804); + EXPECT_EQ(Crc32fpb(RANDOM_12_BYTES, sizeof(RANDOM_12_BYTES)), (uint32_t)0xe6e82b53); + EXPECT_EQ(Crc32fpb(RANDOM_13_BYTES, sizeof(RANDOM_13_BYTES)), (uint32_t)0x80f65532); + EXPECT_EQ(Crc32fpb(RANDOM_14_BYTES, sizeof(RANDOM_14_BYTES)), (uint32_t)0xe182e0d6); + EXPECT_EQ(Crc32fpb(RANDOM_15_BYTES, sizeof(RANDOM_15_BYTES)), (uint32_t)0x048fe6a3); + EXPECT_EQ(Crc32fpb(RANDOM_16_BYTES, sizeof(RANDOM_16_BYTES)), (uint32_t)0xc327e431); + EXPECT_EQ(Crc32fpb(RANDOM_29_BYTES, sizeof(RANDOM_29_BYTES)), (uint32_t)0xbc0293a0); + EXPECT_EQ(Crc32fpb(RANDOM_30_BYTES, sizeof(RANDOM_30_BYTES)), (uint32_t)0x32b413b3); + EXPECT_EQ(Crc32fpb(RANDOM_31_BYTES, sizeof(RANDOM_31_BYTES)), (uint32_t)0x8e1c0611); + EXPECT_EQ(Crc32fpb(RANDOM_32_BYTES, sizeof(RANDOM_32_BYTES)), (uint32_t)0xd5307d0d); + EXPECT_EQ(Crc32fpb(RANDOM_64_BYTES, sizeof(RANDOM_64_BYTES)), (uint32_t)0xabbbb8f9); +} + +// --------------------------------------------------------------------------------------------------------------------- + +TEST(CrcTest, Crc24rtcm3) +{ + // Bad input should lead to 0 CRC + EXPECT_EQ(Crc24rtcm3(NULL, 0), (uint32_t)0x000000); + EXPECT_EQ(Crc24rtcm3(NULL, 1), (uint32_t)0x000000); + EXPECT_EQ(Crc24rtcm3(RANDOM_64_BYTES, 0), (uint32_t)0x000000); + // Actual data + EXPECT_EQ(Crc24rtcm3(RANDOM_1_BYTE, sizeof(RANDOM_1_BYTE)), (uint32_t)0x007c943f); + EXPECT_EQ(Crc24rtcm3(RANDOM_2_BYTES, sizeof(RANDOM_2_BYTES)), (uint32_t)0x004a6d00); + EXPECT_EQ(Crc24rtcm3(RANDOM_3_BYTES, sizeof(RANDOM_3_BYTES)), (uint32_t)0x000c5b04); + EXPECT_EQ(Crc24rtcm3(RANDOM_4_BYTES, sizeof(RANDOM_4_BYTES)), (uint32_t)0x0082465c); + EXPECT_EQ(Crc24rtcm3(RANDOM_5_BYTES, sizeof(RANDOM_5_BYTES)), (uint32_t)0x007b800f); + EXPECT_EQ(Crc24rtcm3(RANDOM_6_BYTES, sizeof(RANDOM_6_BYTES)), (uint32_t)0x00993123); + EXPECT_EQ(Crc24rtcm3(RANDOM_7_BYTES, sizeof(RANDOM_7_BYTES)), (uint32_t)0x001056bb); + EXPECT_EQ(Crc24rtcm3(RANDOM_8_BYTES, sizeof(RANDOM_8_BYTES)), (uint32_t)0x00bfdb4a); + EXPECT_EQ(Crc24rtcm3(RANDOM_9_BYTES, sizeof(RANDOM_9_BYTES)), (uint32_t)0x005f3ea2); + EXPECT_EQ(Crc24rtcm3(RANDOM_10_BYTES, sizeof(RANDOM_10_BYTES)), (uint32_t)0x00ec5fbd); + EXPECT_EQ(Crc24rtcm3(RANDOM_11_BYTES, sizeof(RANDOM_11_BYTES)), (uint32_t)0x00e4e1e0); + EXPECT_EQ(Crc24rtcm3(RANDOM_12_BYTES, sizeof(RANDOM_12_BYTES)), (uint32_t)0x001e46af); + EXPECT_EQ(Crc24rtcm3(RANDOM_13_BYTES, sizeof(RANDOM_13_BYTES)), (uint32_t)0x00f68a9b); + EXPECT_EQ(Crc24rtcm3(RANDOM_14_BYTES, sizeof(RANDOM_14_BYTES)), (uint32_t)0x00dd2d74); + EXPECT_EQ(Crc24rtcm3(RANDOM_15_BYTES, sizeof(RANDOM_15_BYTES)), (uint32_t)0x001df608); + EXPECT_EQ(Crc24rtcm3(RANDOM_16_BYTES, sizeof(RANDOM_16_BYTES)), (uint32_t)0x008b2c7d); + EXPECT_EQ(Crc24rtcm3(RANDOM_29_BYTES, sizeof(RANDOM_29_BYTES)), (uint32_t)0x00ff1037); + EXPECT_EQ(Crc24rtcm3(RANDOM_30_BYTES, sizeof(RANDOM_30_BYTES)), (uint32_t)0x00a5b132); + EXPECT_EQ(Crc24rtcm3(RANDOM_31_BYTES, sizeof(RANDOM_31_BYTES)), (uint32_t)0x003e9621); + EXPECT_EQ(Crc24rtcm3(RANDOM_32_BYTES, sizeof(RANDOM_32_BYTES)), (uint32_t)0x00ef5580); + EXPECT_EQ(Crc24rtcm3(RANDOM_64_BYTES, sizeof(RANDOM_64_BYTES)), (uint32_t)0x005d4034); +} + +// --------------------------------------------------------------------------------------------------------------------- + +TEST(CrcTest, Crc32novb) +{ + // Bad input should lead to 0 CRC + EXPECT_EQ(Crc32novb(NULL, 0), (uint32_t)0x00000000); + EXPECT_EQ(Crc32novb(NULL, 1), (uint32_t)0x00000000); + EXPECT_EQ(Crc32novb(RANDOM_64_BYTES, 0), (uint32_t)0x00000000); + // Actual data + EXPECT_EQ(Crc32novb(RANDOM_1_BYTE, sizeof(RANDOM_1_BYTE)), (uint32_t)0xbc66831a); + EXPECT_EQ(Crc32novb(RANDOM_2_BYTES, sizeof(RANDOM_2_BYTES)), (uint32_t)0x02a5445b); + EXPECT_EQ(Crc32novb(RANDOM_3_BYTES, sizeof(RANDOM_3_BYTES)), (uint32_t)0x1aa4e1bf); + EXPECT_EQ(Crc32novb(RANDOM_4_BYTES, sizeof(RANDOM_4_BYTES)), (uint32_t)0x68bfa9ae); + EXPECT_EQ(Crc32novb(RANDOM_5_BYTES, sizeof(RANDOM_5_BYTES)), (uint32_t)0x442131ff); + EXPECT_EQ(Crc32novb(RANDOM_6_BYTES, sizeof(RANDOM_6_BYTES)), (uint32_t)0xace112b0); + EXPECT_EQ(Crc32novb(RANDOM_7_BYTES, sizeof(RANDOM_7_BYTES)), (uint32_t)0x7d609de8); + EXPECT_EQ(Crc32novb(RANDOM_8_BYTES, sizeof(RANDOM_8_BYTES)), (uint32_t)0x27bcf013); + EXPECT_EQ(Crc32novb(RANDOM_9_BYTES, sizeof(RANDOM_9_BYTES)), (uint32_t)0xeb46e4df); + EXPECT_EQ(Crc32novb(RANDOM_10_BYTES, sizeof(RANDOM_10_BYTES)), (uint32_t)0xde30a04d); + EXPECT_EQ(Crc32novb(RANDOM_11_BYTES, sizeof(RANDOM_11_BYTES)), (uint32_t)0xd6597dc0); + EXPECT_EQ(Crc32novb(RANDOM_12_BYTES, sizeof(RANDOM_12_BYTES)), (uint32_t)0xd1a01f30); + EXPECT_EQ(Crc32novb(RANDOM_13_BYTES, sizeof(RANDOM_13_BYTES)), (uint32_t)0x31100903); + EXPECT_EQ(Crc32novb(RANDOM_14_BYTES, sizeof(RANDOM_14_BYTES)), (uint32_t)0x69bab6dd); + EXPECT_EQ(Crc32novb(RANDOM_15_BYTES, sizeof(RANDOM_15_BYTES)), (uint32_t)0xe3f3d424); + EXPECT_EQ(Crc32novb(RANDOM_16_BYTES, sizeof(RANDOM_16_BYTES)), (uint32_t)0x9831d368); + EXPECT_EQ(Crc32novb(RANDOM_29_BYTES, sizeof(RANDOM_29_BYTES)), (uint32_t)0x6cf9627d); + EXPECT_EQ(Crc32novb(RANDOM_30_BYTES, sizeof(RANDOM_30_BYTES)), (uint32_t)0xaf485c94); + EXPECT_EQ(Crc32novb(RANDOM_31_BYTES, sizeof(RANDOM_31_BYTES)), (uint32_t)0x87fd4627); + EXPECT_EQ(Crc32novb(RANDOM_32_BYTES, sizeof(RANDOM_32_BYTES)), (uint32_t)0x063804b7); + EXPECT_EQ(Crc32novb(RANDOM_64_BYTES, sizeof(RANDOM_64_BYTES)), (uint32_t)0xe898a950); +} + +// --------------------------------------------------------------------------------------------------------------------- + +TEST(CrcTest, Crc4spartn) +{ + // Bad input should lead to 0 CRC + EXPECT_EQ(Crc4spartn(NULL, 0), (uint8_t)0x0); + EXPECT_EQ(Crc4spartn(NULL, 1), (uint8_t)0x0); + EXPECT_EQ(Crc4spartn(RANDOM_64_BYTES, 0), (uint8_t)0x0); + // Actual data + EXPECT_EQ(Crc4spartn(RANDOM_1_BYTE, sizeof(RANDOM_1_BYTE)), (uint8_t)0x3); + EXPECT_EQ(Crc4spartn(RANDOM_2_BYTES, sizeof(RANDOM_2_BYTES)), (uint8_t)0x9); + EXPECT_EQ(Crc4spartn(RANDOM_3_BYTES, sizeof(RANDOM_3_BYTES)), (uint8_t)0x6); + EXPECT_EQ(Crc4spartn(RANDOM_4_BYTES, sizeof(RANDOM_4_BYTES)), (uint8_t)0xf); + EXPECT_EQ(Crc4spartn(RANDOM_5_BYTES, sizeof(RANDOM_5_BYTES)), (uint8_t)0x3); + EXPECT_EQ(Crc4spartn(RANDOM_6_BYTES, sizeof(RANDOM_6_BYTES)), (uint8_t)0x7); + EXPECT_EQ(Crc4spartn(RANDOM_7_BYTES, sizeof(RANDOM_7_BYTES)), (uint8_t)0x7); + EXPECT_EQ(Crc4spartn(RANDOM_8_BYTES, sizeof(RANDOM_8_BYTES)), (uint8_t)0x1); + EXPECT_EQ(Crc4spartn(RANDOM_9_BYTES, sizeof(RANDOM_9_BYTES)), (uint8_t)0x1); + EXPECT_EQ(Crc4spartn(RANDOM_10_BYTES, sizeof(RANDOM_10_BYTES)), (uint8_t)0x9); + EXPECT_EQ(Crc4spartn(RANDOM_11_BYTES, sizeof(RANDOM_11_BYTES)), (uint8_t)0x6); + EXPECT_EQ(Crc4spartn(RANDOM_12_BYTES, sizeof(RANDOM_12_BYTES)), (uint8_t)0x7); + EXPECT_EQ(Crc4spartn(RANDOM_13_BYTES, sizeof(RANDOM_13_BYTES)), (uint8_t)0xc); + EXPECT_EQ(Crc4spartn(RANDOM_14_BYTES, sizeof(RANDOM_14_BYTES)), (uint8_t)0x6); + EXPECT_EQ(Crc4spartn(RANDOM_15_BYTES, sizeof(RANDOM_15_BYTES)), (uint8_t)0x5); + EXPECT_EQ(Crc4spartn(RANDOM_16_BYTES, sizeof(RANDOM_16_BYTES)), (uint8_t)0xc); + EXPECT_EQ(Crc4spartn(RANDOM_29_BYTES, sizeof(RANDOM_29_BYTES)), (uint8_t)0x4); + EXPECT_EQ(Crc4spartn(RANDOM_30_BYTES, sizeof(RANDOM_30_BYTES)), (uint8_t)0xb); + EXPECT_EQ(Crc4spartn(RANDOM_31_BYTES, sizeof(RANDOM_31_BYTES)), (uint8_t)0x2); + EXPECT_EQ(Crc4spartn(RANDOM_32_BYTES, sizeof(RANDOM_32_BYTES)), (uint8_t)0xe); + EXPECT_EQ(Crc4spartn(RANDOM_64_BYTES, sizeof(RANDOM_64_BYTES)), (uint8_t)0xb); +} + +// --------------------------------------------------------------------------------------------------------------------- + +TEST(CrcTest, Crc8spartn) +{ + // Bad input should lead to 0 CRC + EXPECT_EQ(Crc8spartn(NULL, 0), (uint8_t)0x00); + EXPECT_EQ(Crc8spartn(NULL, 1), (uint8_t)0x00); + EXPECT_EQ(Crc8spartn(RANDOM_64_BYTES, 0), (uint8_t)0x00); + // Actual data + EXPECT_EQ(Crc8spartn(RANDOM_1_BYTE, sizeof(RANDOM_1_BYTE)), (uint8_t)0x1e); + EXPECT_EQ(Crc8spartn(RANDOM_2_BYTES, sizeof(RANDOM_2_BYTES)), (uint8_t)0x1d); + EXPECT_EQ(Crc8spartn(RANDOM_3_BYTES, sizeof(RANDOM_3_BYTES)), (uint8_t)0x0c); + EXPECT_EQ(Crc8spartn(RANDOM_4_BYTES, sizeof(RANDOM_4_BYTES)), (uint8_t)0xd3); + EXPECT_EQ(Crc8spartn(RANDOM_5_BYTES, sizeof(RANDOM_5_BYTES)), (uint8_t)0x08); + EXPECT_EQ(Crc8spartn(RANDOM_6_BYTES, sizeof(RANDOM_6_BYTES)), (uint8_t)0xeb); + EXPECT_EQ(Crc8spartn(RANDOM_7_BYTES, sizeof(RANDOM_7_BYTES)), (uint8_t)0x2c); + EXPECT_EQ(Crc8spartn(RANDOM_8_BYTES, sizeof(RANDOM_8_BYTES)), (uint8_t)0xb2); + EXPECT_EQ(Crc8spartn(RANDOM_9_BYTES, sizeof(RANDOM_9_BYTES)), (uint8_t)0x8d); + EXPECT_EQ(Crc8spartn(RANDOM_10_BYTES, sizeof(RANDOM_10_BYTES)), (uint8_t)0x34); + EXPECT_EQ(Crc8spartn(RANDOM_11_BYTES, sizeof(RANDOM_11_BYTES)), (uint8_t)0x9e); + EXPECT_EQ(Crc8spartn(RANDOM_12_BYTES, sizeof(RANDOM_12_BYTES)), (uint8_t)0xab); + EXPECT_EQ(Crc8spartn(RANDOM_13_BYTES, sizeof(RANDOM_13_BYTES)), (uint8_t)0xcc); + EXPECT_EQ(Crc8spartn(RANDOM_14_BYTES, sizeof(RANDOM_14_BYTES)), (uint8_t)0xe2); + EXPECT_EQ(Crc8spartn(RANDOM_15_BYTES, sizeof(RANDOM_15_BYTES)), (uint8_t)0x20); + EXPECT_EQ(Crc8spartn(RANDOM_16_BYTES, sizeof(RANDOM_16_BYTES)), (uint8_t)0xd5); + EXPECT_EQ(Crc8spartn(RANDOM_29_BYTES, sizeof(RANDOM_29_BYTES)), (uint8_t)0xaa); + EXPECT_EQ(Crc8spartn(RANDOM_30_BYTES, sizeof(RANDOM_30_BYTES)), (uint8_t)0xb5); + EXPECT_EQ(Crc8spartn(RANDOM_31_BYTES, sizeof(RANDOM_31_BYTES)), (uint8_t)0x13); + EXPECT_EQ(Crc8spartn(RANDOM_32_BYTES, sizeof(RANDOM_32_BYTES)), (uint8_t)0x71); + EXPECT_EQ(Crc8spartn(RANDOM_64_BYTES, sizeof(RANDOM_64_BYTES)), (uint8_t)0xe6); +} + +// --------------------------------------------------------------------------------------------------------------------- + +TEST(CrcTest, Crc16spartn) +{ + // Bad input should lead to 0 CRC + EXPECT_EQ(Crc16spartn(NULL, 0), (uint16_t)0x0000); + EXPECT_EQ(Crc16spartn(NULL, 1), (uint16_t)0x0000); + EXPECT_EQ(Crc16spartn(RANDOM_64_BYTES, 0), (uint16_t)0x0000); + // Actual data + EXPECT_EQ(Crc16spartn(RANDOM_1_BYTE, sizeof(RANDOM_1_BYTE)), (uint16_t)0xb7fa); + EXPECT_EQ(Crc16spartn(RANDOM_2_BYTES, sizeof(RANDOM_2_BYTES)), (uint16_t)0x1b50); + EXPECT_EQ(Crc16spartn(RANDOM_3_BYTES, sizeof(RANDOM_3_BYTES)), (uint16_t)0x2661); + EXPECT_EQ(Crc16spartn(RANDOM_4_BYTES, sizeof(RANDOM_4_BYTES)), (uint16_t)0x357a); + EXPECT_EQ(Crc16spartn(RANDOM_5_BYTES, sizeof(RANDOM_5_BYTES)), (uint16_t)0xad69); + EXPECT_EQ(Crc16spartn(RANDOM_6_BYTES, sizeof(RANDOM_6_BYTES)), (uint16_t)0xee82); + EXPECT_EQ(Crc16spartn(RANDOM_7_BYTES, sizeof(RANDOM_7_BYTES)), (uint16_t)0x7779); + EXPECT_EQ(Crc16spartn(RANDOM_8_BYTES, sizeof(RANDOM_8_BYTES)), (uint16_t)0x307e); + EXPECT_EQ(Crc16spartn(RANDOM_9_BYTES, sizeof(RANDOM_9_BYTES)), (uint16_t)0x5475); + EXPECT_EQ(Crc16spartn(RANDOM_10_BYTES, sizeof(RANDOM_10_BYTES)), (uint16_t)0xf1f9); + EXPECT_EQ(Crc16spartn(RANDOM_11_BYTES, sizeof(RANDOM_11_BYTES)), (uint16_t)0x3e0a); + EXPECT_EQ(Crc16spartn(RANDOM_12_BYTES, sizeof(RANDOM_12_BYTES)), (uint16_t)0x8c88); + EXPECT_EQ(Crc16spartn(RANDOM_13_BYTES, sizeof(RANDOM_13_BYTES)), (uint16_t)0x1a70); + EXPECT_EQ(Crc16spartn(RANDOM_14_BYTES, sizeof(RANDOM_14_BYTES)), (uint16_t)0x64ec); + EXPECT_EQ(Crc16spartn(RANDOM_15_BYTES, sizeof(RANDOM_15_BYTES)), (uint16_t)0x0278); + EXPECT_EQ(Crc16spartn(RANDOM_16_BYTES, sizeof(RANDOM_16_BYTES)), (uint16_t)0x5422); + EXPECT_EQ(Crc16spartn(RANDOM_29_BYTES, sizeof(RANDOM_29_BYTES)), (uint16_t)0x30d4); + EXPECT_EQ(Crc16spartn(RANDOM_30_BYTES, sizeof(RANDOM_30_BYTES)), (uint16_t)0x349c); + EXPECT_EQ(Crc16spartn(RANDOM_31_BYTES, sizeof(RANDOM_31_BYTES)), (uint16_t)0xb846); + EXPECT_EQ(Crc16spartn(RANDOM_32_BYTES, sizeof(RANDOM_32_BYTES)), (uint16_t)0xa5e1); + EXPECT_EQ(Crc16spartn(RANDOM_64_BYTES, sizeof(RANDOM_64_BYTES)), (uint16_t)0xc5f4); +} + +// --------------------------------------------------------------------------------------------------------------------- + +TEST(CrcTest, Crc32spartn) +{ + // Bad input should lead to 0 CRC + EXPECT_EQ(Crc32spartn(NULL, 0), (uint32_t)0x00000000); + EXPECT_EQ(Crc32spartn(NULL, 1), (uint32_t)0x00000000); + EXPECT_EQ(Crc32spartn(RANDOM_64_BYTES, 0), (uint32_t)0x00000000); + // Actual data + EXPECT_EQ(Crc32spartn(RANDOM_1_BYTE, sizeof(RANDOM_1_BYTE)), (uint32_t)0x0808d082); + EXPECT_EQ(Crc32spartn(RANDOM_2_BYTES, sizeof(RANDOM_2_BYTES)), (uint32_t)0x568dfe16); + EXPECT_EQ(Crc32spartn(RANDOM_3_BYTES, sizeof(RANDOM_3_BYTES)), (uint32_t)0x15a904d3); + EXPECT_EQ(Crc32spartn(RANDOM_4_BYTES, sizeof(RANDOM_4_BYTES)), (uint32_t)0xff69839b); + EXPECT_EQ(Crc32spartn(RANDOM_5_BYTES, sizeof(RANDOM_5_BYTES)), (uint32_t)0xce450906); + EXPECT_EQ(Crc32spartn(RANDOM_6_BYTES, sizeof(RANDOM_6_BYTES)), (uint32_t)0xa399ff53); + EXPECT_EQ(Crc32spartn(RANDOM_7_BYTES, sizeof(RANDOM_7_BYTES)), (uint32_t)0xd2a22d5b); + EXPECT_EQ(Crc32spartn(RANDOM_8_BYTES, sizeof(RANDOM_8_BYTES)), (uint32_t)0xedd76950); + EXPECT_EQ(Crc32spartn(RANDOM_9_BYTES, sizeof(RANDOM_9_BYTES)), (uint32_t)0x47184985); + EXPECT_EQ(Crc32spartn(RANDOM_10_BYTES, sizeof(RANDOM_10_BYTES)), (uint32_t)0x3fefe99a); + EXPECT_EQ(Crc32spartn(RANDOM_11_BYTES, sizeof(RANDOM_11_BYTES)), (uint32_t)0x76678f10); + EXPECT_EQ(Crc32spartn(RANDOM_12_BYTES, sizeof(RANDOM_12_BYTES)), (uint32_t)0xe861a39d); + EXPECT_EQ(Crc32spartn(RANDOM_13_BYTES, sizeof(RANDOM_13_BYTES)), (uint32_t)0x587d9e0f); + EXPECT_EQ(Crc32spartn(RANDOM_14_BYTES, sizeof(RANDOM_14_BYTES)), (uint32_t)0xa7510e5d); + EXPECT_EQ(Crc32spartn(RANDOM_15_BYTES, sizeof(RANDOM_15_BYTES)), (uint32_t)0xd296dbc2); + EXPECT_EQ(Crc32spartn(RANDOM_16_BYTES, sizeof(RANDOM_16_BYTES)), (uint32_t)0x891679e9); + EXPECT_EQ(Crc32spartn(RANDOM_29_BYTES, sizeof(RANDOM_29_BYTES)), (uint32_t)0x21a40a93); + EXPECT_EQ(Crc32spartn(RANDOM_30_BYTES, sizeof(RANDOM_30_BYTES)), (uint32_t)0xf16fb9b3); + EXPECT_EQ(Crc32spartn(RANDOM_31_BYTES, sizeof(RANDOM_31_BYTES)), (uint32_t)0xab12b0b9); + EXPECT_EQ(Crc32spartn(RANDOM_32_BYTES, sizeof(RANDOM_32_BYTES)), (uint32_t)0x7ffb3664); + EXPECT_EQ(Crc32spartn(RANDOM_64_BYTES, sizeof(RANDOM_64_BYTES)), (uint32_t)0xf2f3867a); +} + +// --------------------------------------------------------------------------------------------------------------------- + +TEST(CrcTest, ChecksumUbx) +{ + // Bad input should lead to 0 CRC + EXPECT_EQ(ChecksumUbx(NULL, 0), (uint16_t)0x0000); + EXPECT_EQ(ChecksumUbx(NULL, 1), (uint16_t)0x0000); + EXPECT_EQ(ChecksumUbx(RANDOM_64_BYTES, 0), (uint16_t)0x0000); + // Actual data + EXPECT_EQ(ChecksumUbx(RANDOM_1_BYTE, sizeof(RANDOM_1_BYTE)), (uint16_t)0xb1b1); + EXPECT_EQ(ChecksumUbx(RANDOM_2_BYTES, sizeof(RANDOM_2_BYTES)), (uint16_t)0xa775); + EXPECT_EQ(ChecksumUbx(RANDOM_3_BYTES, sizeof(RANDOM_3_BYTES)), (uint16_t)0xc7ce); + EXPECT_EQ(ChecksumUbx(RANDOM_4_BYTES, sizeof(RANDOM_4_BYTES)), (uint16_t)0x0e30); + EXPECT_EQ(ChecksumUbx(RANDOM_5_BYTES, sizeof(RANDOM_5_BYTES)), (uint16_t)0x6b22); + EXPECT_EQ(ChecksumUbx(RANDOM_6_BYTES, sizeof(RANDOM_6_BYTES)), (uint16_t)0xd46a); + EXPECT_EQ(ChecksumUbx(RANDOM_7_BYTES, sizeof(RANDOM_7_BYTES)), (uint16_t)0xfa11); + EXPECT_EQ(ChecksumUbx(RANDOM_8_BYTES, sizeof(RANDOM_8_BYTES)), (uint16_t)0xd56a); + EXPECT_EQ(ChecksumUbx(RANDOM_9_BYTES, sizeof(RANDOM_9_BYTES)), (uint16_t)0xc140); + EXPECT_EQ(ChecksumUbx(RANDOM_10_BYTES, sizeof(RANDOM_10_BYTES)), (uint16_t)0xb152); + EXPECT_EQ(ChecksumUbx(RANDOM_11_BYTES, sizeof(RANDOM_11_BYTES)), (uint16_t)0x5223); + EXPECT_EQ(ChecksumUbx(RANDOM_12_BYTES, sizeof(RANDOM_12_BYTES)), (uint16_t)0x569b); + EXPECT_EQ(ChecksumUbx(RANDOM_13_BYTES, sizeof(RANDOM_13_BYTES)), (uint16_t)0x6896); + EXPECT_EQ(ChecksumUbx(RANDOM_14_BYTES, sizeof(RANDOM_14_BYTES)), (uint16_t)0x9787); + EXPECT_EQ(ChecksumUbx(RANDOM_15_BYTES, sizeof(RANDOM_15_BYTES)), (uint16_t)0x191b); + EXPECT_EQ(ChecksumUbx(RANDOM_16_BYTES, sizeof(RANDOM_16_BYTES)), (uint16_t)0x9a81); + EXPECT_EQ(ChecksumUbx(RANDOM_29_BYTES, sizeof(RANDOM_29_BYTES)), (uint16_t)0xe959); + EXPECT_EQ(ChecksumUbx(RANDOM_30_BYTES, sizeof(RANDOM_30_BYTES)), (uint16_t)0xb70b); + EXPECT_EQ(ChecksumUbx(RANDOM_31_BYTES, sizeof(RANDOM_31_BYTES)), (uint16_t)0xcc76); + EXPECT_EQ(ChecksumUbx(RANDOM_32_BYTES, sizeof(RANDOM_32_BYTES)), (uint16_t)0x0f55); + EXPECT_EQ(ChecksumUbx(RANDOM_64_BYTES, sizeof(RANDOM_64_BYTES)), (uint16_t)0xa2b4); +} + +/* ****************************************************************************************************************** */ +} // namespace + +int main(int argc, char** argv) +{ + testing::InitGoogleTest(&argc, argv); + auto level = fpsdk::common::logging::LoggingLevel::WARNING; + for (int ix = 0; ix < argc; ix++) { + if ((argv[ix][0] == '-') && argv[ix][1] == 'v') { + level++; + } + } + fpsdk::common::logging::LoggingSetParams(level); + return RUN_ALL_TESTS(); +} diff --git a/fpsdk_common/test/parser_fpa_test.cpp b/fpsdk_common/test/parser_fpa_test.cpp new file mode 100644 index 0000000..622df79 --- /dev/null +++ b/fpsdk_common/test/parser_fpa_test.cpp @@ -0,0 +1,790 @@ +/** + * \verbatim + * ___ ___ + * \ \ / / + * \ \/ / Copyright (c) Fixposition AG (www.fixposition.com) and contributors + * / /\ \ License: see the LICENSE file + * /__/ \__\ + * \endverbatim + * + * @file + * @brief Fixposition SDK: tests for fpsdk::common::parser::fpa + */ + +/* LIBC/STL */ +#include + +/* EXTERNAL */ +#include + +/* PACKAGE */ +#include +#include + +namespace { +/* ****************************************************************************************************************** */ +using namespace fpsdk::common::parser::fpa; + +TEST(ParserFpaTest, FpaGetMessageMeta) +{ + { + // 012345678901234567890123456789 + // TTTTTTTT V PPPPPPPPPPP + const char* msg = "$FP,ODOMETRY,1,...,...,...*xx\r\n"; + FpaMessageMeta meta; + EXPECT_TRUE(FpaGetMessageMeta(meta, (const uint8_t*)msg, strlen(msg))) << msg; + EXPECT_EQ(std::string(meta.msg_type_), std::string("ODOMETRY")) << msg; + EXPECT_EQ(meta.msg_version_, 1) << msg; + EXPECT_EQ(meta.payload_ix0_, 15) << msg; + EXPECT_EQ(meta.payload_ix1_, 25) << msg; + } + { + // 012345678901234567890123456789 + // TTTTTTTT V + const char* msg = "$FP,ODOMETRY,1*xx\r\n"; + FpaMessageMeta meta; + EXPECT_TRUE(FpaGetMessageMeta(meta, (const uint8_t*)msg, strlen(msg))) << msg; + EXPECT_EQ(std::string(meta.msg_type_), std::string("ODOMETRY")) << msg; + EXPECT_EQ(meta.msg_version_, 1) << msg; + EXPECT_EQ(meta.payload_ix0_, 0) << msg; + EXPECT_EQ(meta.payload_ix1_, 0) << msg; + } + { + // 012345678901234567890123456789 + // TTTTTTTT + const char* msg = "$FP,ODOMETRY*xx\r\n"; + FpaMessageMeta meta; + EXPECT_TRUE(FpaGetMessageMeta(meta, (const uint8_t*)msg, strlen(msg))) << msg; + EXPECT_EQ(std::string(meta.msg_type_), std::string("ODOMETRY")) << msg; + EXPECT_LT(meta.msg_version_, 0) << msg; + EXPECT_EQ(meta.payload_ix0_, 0) << msg; + EXPECT_EQ(meta.payload_ix1_, 0) << msg; + } + { + // 012345678901234567890123456789 + // TTTTTTTT + const char* msg = "$FP,ODOMETRY,*xx\r\n"; + FpaMessageMeta meta; + EXPECT_TRUE(FpaGetMessageMeta(meta, (const uint8_t*)msg, strlen(msg))) << msg; + EXPECT_EQ(std::string(meta.msg_type_), std::string("ODOMETRY")) << msg; + EXPECT_LT(meta.msg_version_, 0) << msg; + EXPECT_EQ(meta.payload_ix0_, 0) << msg; + EXPECT_EQ(meta.payload_ix1_, 0) << msg; + } + { + // 012345678901234567890123456789 + // TTTTTTTT + const char* msg = "$FP,ODOMETRY,notanumber*xx\r\n"; + FpaMessageMeta meta; + EXPECT_TRUE(FpaGetMessageMeta(meta, (const uint8_t*)msg, strlen(msg))) << msg; + EXPECT_EQ(std::string(meta.msg_type_), std::string("ODOMETRY")) << msg; + EXPECT_LT(meta.msg_version_, 0) << msg; + EXPECT_EQ(meta.payload_ix0_, 13) << msg; + EXPECT_EQ(meta.payload_ix1_, 22) << msg; + } + // Bad input + { + const char* msg = "whateverwhatever"; + FpaMessageMeta meta; + EXPECT_FALSE(FpaGetMessageMeta(meta, NULL, 0)) << msg; + EXPECT_FALSE(FpaGetMessageMeta(meta, NULL, -1)) << msg; + EXPECT_FALSE(FpaGetMessageMeta(meta, (const uint8_t*)msg, 0)) << msg; + EXPECT_FALSE(FpaGetMessageMeta(meta, (const uint8_t*)msg, -1)) << msg; + } + { + const char* msg = "$ABCDEFGHIJKLMNOP"; + FpaMessageMeta meta; + EXPECT_FALSE(FpaGetMessageMeta(meta, (const uint8_t*)msg, strlen(msg))); + } + { + const char* msg = "$GNABCDEFGHIJKLMNOPQRSTUVW,123,456,789*xx\r\n"; + FpaMessageMeta meta; + EXPECT_FALSE(FpaGetMessageMeta(meta, (const uint8_t*)msg, strlen(msg))) << msg; + EXPECT_EQ(std::string(meta.msg_type_), std::string("")) << msg; + EXPECT_EQ(meta.msg_version_, 0) << msg; + EXPECT_EQ(meta.payload_ix0_, 0) << msg; + EXPECT_EQ(meta.payload_ix1_, 0) << msg; + } +} + +// --------------------------------------------------------------------------------------------------------------------- + +TEST(ParserFpaTest, FpaGetMessageName) +{ + { + const char* msg = "$FP,ODOMETRY,1,...,...,...*xx\r\n"; + char name[100]; + EXPECT_TRUE(FpaGetMessageName(name, sizeof(name), (const uint8_t*)msg, strlen(msg))) << msg; + EXPECT_EQ(std::string(name), std::string("FP_A-ODOMETRY")) << msg; + } + { + const char* msg = "$FP,ODOMETRY,1*xx\r\n"; + char name[100]; + EXPECT_TRUE(FpaGetMessageName(name, sizeof(name), (const uint8_t*)msg, strlen(msg))) << msg; + EXPECT_EQ(std::string(name), std::string("FP_A-ODOMETRY")) << msg; + } + { + const char* msg = "$FP,ODOMETRY,X*xx\r\n"; // Bad msg_version + char name[100]; + EXPECT_TRUE(FpaGetMessageName(name, sizeof(name), (const uint8_t*)msg, strlen(msg))) << msg; + EXPECT_EQ(std::string(name), std::string("FP_A-ODOMETRY")) << msg; + } + // Bad input + { + const char* msg = "whateverwhatever"; + char name[100]; + EXPECT_FALSE(FpaGetMessageName(name, sizeof(name), NULL, 0)) << msg; + EXPECT_FALSE(FpaGetMessageName(name, sizeof(name), NULL, -1)) << msg; + EXPECT_FALSE(FpaGetMessageName(name, sizeof(name), (const uint8_t*)msg, 0)) << msg; + EXPECT_FALSE(FpaGetMessageName(name, sizeof(name), (const uint8_t*)msg, -1)) << msg; + EXPECT_FALSE(FpaGetMessageName(NULL, 0, (const uint8_t*)msg, sizeof(msg))) << msg; + EXPECT_FALSE(FpaGetMessageName(NULL, -1, (const uint8_t*)msg, sizeof(msg))) << msg; + EXPECT_FALSE(FpaGetMessageName(name, 0, (const uint8_t*)msg, sizeof(msg))) << msg; + EXPECT_FALSE(FpaGetMessageName(name, -1, (const uint8_t*)msg, sizeof(msg))) << msg; + EXPECT_FALSE(FpaGetMessageName(NULL, 0, NULL, 0)) << msg; + EXPECT_FALSE(FpaGetMessageName(NULL, 0, NULL, -1)) << msg; + } +} + +// --------------------------------------------------------------------------------------------------------------------- + +TEST(FpaTest, FpaGpsTime) +{ + const FpaGpsTime t1; + const FpaGpsTime t2 = { { true, 1234 }, { true, 456789.123456 } }; + const FpaGpsTime t3 = { { true, 1234 }, { true, 456789.123457 } }; + const FpaGpsTime t4 = { { true, 1235 }, { true, 456789.123456 } }; + const FpaGpsTime t5 = { { true, 1235 }, { true, 456789.1234564 } }; + + EXPECT_EQ(t1, t1); + EXPECT_EQ(t2, t2); + EXPECT_NE(t1, t2); + + EXPECT_GT(t3, t2); + EXPECT_GT(t4, t3); + EXPECT_GT(t4, t2); + + EXPECT_LT(t2, t3); + EXPECT_LT(t3, t4); + EXPECT_LT(t2, t4); + + EXPECT_GE(t3, t2); + EXPECT_GE(t4, t3); + EXPECT_GE(t4, t2); + + EXPECT_LE(t2, t3); + EXPECT_LE(t3, t4); + EXPECT_LE(t2, t4); + + EXPECT_EQ(t5, t4); + EXPECT_GE(t5, t4); + EXPECT_LE(t4, t5); +} + +// --------------------------------------------------------------------------------------------------------------------- + +TEST(FpaTest, FpaEoePayload) +{ + { + FpaEoePayload payload; + const char* msg = "$FP,EOE,1,2322,309663.800000,FUSION*62\r\n"; + EXPECT_TRUE(payload.SetFromMsg((const uint8_t*)msg, strlen(msg))); + EXPECT_TRUE(payload.gps_time.week.valid); + EXPECT_EQ(payload.gps_time.week.value, 2322); + EXPECT_TRUE(payload.gps_time.tow.valid); + EXPECT_NEAR(payload.gps_time.tow.value, 309663.8, 1e-9); + EXPECT_EQ(payload.epoch, FpaEpoch::FUSION); + } + { + FpaEoePayload payload; + const char* msg = "$FP,EOE,1,,,GNSS1*7C\r\n"; + EXPECT_TRUE(payload.SetFromMsg((const uint8_t*)msg, strlen(msg))); + EXPECT_FALSE(payload.gps_time.week.valid); + EXPECT_EQ(payload.gps_time.week.value, 0); + EXPECT_FALSE(payload.gps_time.tow.valid); + EXPECT_EQ(payload.gps_time.tow.value, 0.0); + EXPECT_EQ(payload.epoch, FpaEpoch::GNSS1); + } + { + FpaEoePayload payload; + const char* msg = "$FP,EOE,1,,,CHABIS*XX\r\n"; + EXPECT_FALSE(payload.SetFromMsg((const uint8_t*)msg, strlen(msg))); + EXPECT_FALSE(payload.gps_time.week.valid); + EXPECT_EQ(payload.gps_time.week.value, 0); + EXPECT_FALSE(payload.gps_time.tow.valid); + EXPECT_EQ(payload.gps_time.tow.value, 0.0); + EXPECT_EQ(payload.epoch, FpaEpoch::UNSPECIFIED); + } +} + +// --------------------------------------------------------------------------------------------------------------------- + +TEST(FpaTest, FpaGnssantPayload) +{ + { + FpaGnssantPayload payload; + const char* msg = "$FP,GNSSANT,1,2234,305129.200151,short,off,0,open,on,28*65\r\n"; + EXPECT_TRUE(payload.SetFromMsg((const uint8_t*)msg, strlen(msg))); + EXPECT_TRUE(payload.gps_time.week.valid); + EXPECT_EQ(payload.gps_time.week.value, 2234); + EXPECT_TRUE(payload.gps_time.tow.valid); + EXPECT_NEAR(payload.gps_time.tow.value, 305129.200151, 1e-9); + EXPECT_EQ(payload.gnss1_state, FpaAntState::SHORT); + EXPECT_EQ(payload.gnss1_power, FpaAntPower::OFF); + EXPECT_TRUE(payload.gnss1_age.valid); + EXPECT_EQ(payload.gnss1_age.value, 0); + EXPECT_EQ(payload.gnss2_state, FpaAntState::OPEN); + EXPECT_EQ(payload.gnss2_power, FpaAntPower::ON); + EXPECT_TRUE(payload.gnss2_age.valid); + EXPECT_EQ(payload.gnss2_age.value, 28); + } + { + FpaGnssantPayload payload; + const char* msg = "$FP,GNSSANT,1,,,,,,,,*XX\r\n"; + EXPECT_TRUE(payload.SetFromMsg((const uint8_t*)msg, strlen(msg))); + EXPECT_FALSE(payload.gps_time.week.valid); + EXPECT_EQ(payload.gps_time.week.value, 0); + EXPECT_FALSE(payload.gps_time.tow.valid); + EXPECT_EQ(payload.gps_time.tow.value, 0.0); + EXPECT_EQ(payload.gnss1_state, FpaAntState::UNSPECIFIED); + EXPECT_EQ(payload.gnss1_power, FpaAntPower::UNSPECIFIED); + EXPECT_FALSE(payload.gnss1_age.valid); + EXPECT_EQ(payload.gnss1_age.value, 0); + EXPECT_EQ(payload.gnss2_state, FpaAntState::UNSPECIFIED); + EXPECT_EQ(payload.gnss2_power, FpaAntPower::UNSPECIFIED); + EXPECT_FALSE(payload.gnss2_age.valid); + EXPECT_EQ(payload.gnss2_age.value, 0); + } +} + +// --------------------------------------------------------------------------------------------------------------------- + +TEST(FpaTest, FpaGnsscorrPayload) +{ + { + FpaGnsscorrPayload payload; + const char* msg = // clang-format off + "$FP,GNSSCORR,1,2237,250035.999865,8,25,18,8,25,18,0.2,1.0,0.8,5.3,2,47.366986804,8.532965023,481.1094,7254*3F\r\n"; // clang-format on + EXPECT_TRUE(payload.SetFromMsg((const uint8_t*)msg, strlen(msg))); + EXPECT_TRUE(payload.gps_time.week.valid); + EXPECT_EQ(payload.gps_time.week.value, 2237); + EXPECT_TRUE(payload.gps_time.tow.valid); + EXPECT_NEAR(payload.gps_time.tow.value, 250035.999865, 1e-9); + EXPECT_EQ(payload.gnss1_fix, FpaGnssFix::RTK_FIXED); + EXPECT_TRUE(payload.gnss1_nsig_l1.valid); + EXPECT_EQ(payload.gnss1_nsig_l1.value, 25); + EXPECT_TRUE(payload.gnss1_nsig_l2.valid); + EXPECT_EQ(payload.gnss1_nsig_l2.value, 18); + EXPECT_EQ(payload.gnss2_fix, FpaGnssFix::RTK_FIXED); + EXPECT_TRUE(payload.gnss2_nsig_l1.valid); + EXPECT_EQ(payload.gnss2_nsig_l1.value, 25); + EXPECT_TRUE(payload.gnss2_nsig_l2.valid); + EXPECT_EQ(payload.gnss2_nsig_l2.value, 18); + EXPECT_TRUE(payload.corr_latency.valid); + EXPECT_NEAR(payload.corr_latency.value, 0.2, 1e-3); + EXPECT_TRUE(payload.corr_update_rate.valid); + EXPECT_NEAR(payload.corr_update_rate.value, 1.0, 1e-3); + EXPECT_TRUE(payload.corr_data_rate.valid); + EXPECT_NEAR(payload.corr_data_rate.value, 0.8, 1e-3); + EXPECT_TRUE(payload.corr_msg_rate.valid); + EXPECT_NEAR(payload.corr_msg_rate.value, 5.3, 1e-3); + EXPECT_TRUE(payload.sta_id.valid); + EXPECT_EQ(payload.sta_id.value, 2); + EXPECT_TRUE(payload.sta_llh.valid); + EXPECT_NEAR(payload.sta_llh.values[0], 47.366986804, 1e-9); + EXPECT_NEAR(payload.sta_llh.values[1], 8.532965023, 1e-9); + EXPECT_NEAR(payload.sta_llh.values[2], 481.1094, 1e-4); + EXPECT_TRUE(payload.sta_dist.valid); + EXPECT_EQ(payload.sta_dist.value, 7254); + } + { + FpaGnsscorrPayload payload; + const char* msg = "$FP,GNSSCORR,1,2237,250548.999744,8,25,18,8,25,18,,,,,,,,,*24\r\n"; + EXPECT_TRUE(payload.SetFromMsg((const uint8_t*)msg, strlen(msg))); + EXPECT_TRUE(payload.gps_time.week.valid); + EXPECT_EQ(payload.gps_time.week.value, 2237); + EXPECT_TRUE(payload.gps_time.tow.valid); + EXPECT_NEAR(payload.gps_time.tow.value, 250548.999744, 1e-9); + + EXPECT_EQ(payload.gnss1_fix, FpaGnssFix::RTK_FIXED); + EXPECT_TRUE(payload.gnss1_nsig_l1.valid); + EXPECT_EQ(payload.gnss1_nsig_l1.value, 25); + EXPECT_TRUE(payload.gnss1_nsig_l2.valid); + EXPECT_EQ(payload.gnss1_nsig_l2.value, 18); + EXPECT_EQ(payload.gnss2_fix, FpaGnssFix::RTK_FIXED); + EXPECT_TRUE(payload.gnss2_nsig_l1.valid); + EXPECT_EQ(payload.gnss2_nsig_l1.value, 25); + EXPECT_TRUE(payload.gnss2_nsig_l2.valid); + EXPECT_EQ(payload.gnss2_nsig_l2.value, 18); + EXPECT_FALSE(payload.corr_latency.valid); + EXPECT_EQ(payload.corr_latency.value, 0.0); + EXPECT_FALSE(payload.corr_update_rate.valid); + EXPECT_EQ(payload.corr_update_rate.value, 0.0); + EXPECT_FALSE(payload.corr_data_rate.valid); + EXPECT_EQ(payload.corr_data_rate.value, 0.0); + EXPECT_FALSE(payload.corr_msg_rate.valid); + EXPECT_EQ(payload.corr_msg_rate.value, 0.0); + EXPECT_FALSE(payload.sta_id.valid); + EXPECT_EQ(payload.sta_id.value, 0); + EXPECT_FALSE(payload.sta_llh.valid); + EXPECT_EQ(payload.sta_llh.values[0], 0.0); + EXPECT_EQ(payload.sta_llh.values[1], 0.0); + EXPECT_EQ(payload.sta_llh.values[2], 0.0); + EXPECT_FALSE(payload.sta_dist.valid); + EXPECT_EQ(payload.sta_dist.value, 0); + } +} + +// --------------------------------------------------------------------------------------------------------------------- + +TEST(FpaTest, FpaRawimuPayload) +{ + { + FpaRawimuPayload payload; + const char* msg = // clang-format off + "$FP,RAWIMU,1,2197,126191.777855,-0.199914,0.472851,9.917973,0.023436,0.007723,0.002131*34\r\n"; // clang-format on + EXPECT_TRUE(payload.SetFromMsg((const uint8_t*)msg, strlen(msg))); + EXPECT_EQ(payload.which, FpaImuPayload::Which::FP_A_RAWIMU); + EXPECT_TRUE(payload.gps_time.week.valid); + EXPECT_EQ(payload.gps_time.week.value, 2197); + EXPECT_TRUE(payload.gps_time.tow.valid); + EXPECT_NEAR(payload.gps_time.tow.value, 126191.777855, 1e-9); + EXPECT_TRUE(payload.acc.valid); + EXPECT_NEAR(payload.acc.values[0], -0.199914, 1e-9); + EXPECT_NEAR(payload.acc.values[1], 0.472851, 1e-9); + EXPECT_NEAR(payload.acc.values[2], 9.917973, 1e-9); + EXPECT_TRUE(payload.rot.valid); + EXPECT_NEAR(payload.rot.values[0], 0.023436, 1e-9); + EXPECT_NEAR(payload.rot.values[1], 0.007723, 1e-9); + EXPECT_NEAR(payload.rot.values[2], 0.002131, 1e-9); + } + { + FpaRawimuPayload payload; + const char* msg = // clang-format off + "$FP,RAWIMU,1,,,,,,,,*XX\r\n"; // clang-format on + EXPECT_TRUE(payload.SetFromMsg((const uint8_t*)msg, strlen(msg))); + EXPECT_EQ(payload.which, FpaImuPayload::Which::FP_A_RAWIMU); + EXPECT_FALSE(payload.gps_time.week.valid); + EXPECT_EQ(payload.gps_time.week.value, 0); + EXPECT_FALSE(payload.gps_time.tow.valid); + EXPECT_EQ(payload.gps_time.tow.value, 0.0); + EXPECT_FALSE(payload.acc.valid); + EXPECT_EQ(payload.acc.values[0], 0.0); + EXPECT_EQ(payload.acc.values[1], 0.0); + EXPECT_EQ(payload.acc.values[2], 0.0); + EXPECT_FALSE(payload.rot.valid); + EXPECT_EQ(payload.rot.values[0], 0.0); + EXPECT_EQ(payload.rot.values[1], 0.0); + EXPECT_EQ(payload.rot.values[2], 0.0); + } +} + +// --------------------------------------------------------------------------------------------------------------------- + +TEST(FpaTest, FpaCorrimuPayload) +{ + { + FpaCorrimuPayload payload; + const char* msg = // clang-format off + "$FP,CORRIMU,1,2197,126191.777855,-0.195224,0.393969,9.869998,0.013342,-0.004620,-0.000728*7D\r\n"; // clang-format on + EXPECT_TRUE(payload.SetFromMsg((const uint8_t*)msg, strlen(msg))); + EXPECT_EQ(payload.which, FpaImuPayload::Which::FP_A_CORRIMU); + EXPECT_TRUE(payload.gps_time.week.valid); + EXPECT_EQ(payload.gps_time.week.value, 2197); + EXPECT_TRUE(payload.gps_time.tow.valid); + EXPECT_NEAR(payload.gps_time.tow.value, 126191.777855, 1e-9); + EXPECT_TRUE(payload.acc.valid); + EXPECT_NEAR(payload.acc.values[0], -0.195224, 1e-9); + EXPECT_NEAR(payload.acc.values[1], 0.393969, 1e-9); + EXPECT_NEAR(payload.acc.values[2], 9.869998, 1e-9); + EXPECT_TRUE(payload.rot.valid); + EXPECT_NEAR(payload.rot.values[0], 0.013342, 1e-9); + EXPECT_NEAR(payload.rot.values[1], -0.004620, 1e-9); + EXPECT_NEAR(payload.rot.values[2], -0.000728, 1e-9); + } + { + FpaCorrimuPayload payload; + const char* msg = // clang-format off + "$FP,CORRIMU,1,,,,,,,,*XX\r\n"; // clang-format on + EXPECT_TRUE(payload.SetFromMsg((const uint8_t*)msg, strlen(msg))); + EXPECT_EQ(payload.which, FpaImuPayload::Which::FP_A_CORRIMU); + EXPECT_FALSE(payload.gps_time.week.valid); + EXPECT_EQ(payload.gps_time.week.value, 0); + EXPECT_FALSE(payload.gps_time.tow.valid); + EXPECT_EQ(payload.gps_time.tow.value, 0.0); + EXPECT_FALSE(payload.acc.valid); + EXPECT_EQ(payload.acc.values[0], 0.0); + EXPECT_EQ(payload.acc.values[1], 0.0); + EXPECT_EQ(payload.acc.values[2], 0.0); + EXPECT_FALSE(payload.rot.valid); + EXPECT_EQ(payload.rot.values[0], 0.0); + EXPECT_EQ(payload.rot.values[1], 0.0); + EXPECT_EQ(payload.rot.values[2], 0.0); + } +} + +// --------------------------------------------------------------------------------------------------------------------- + +TEST(FpaTest, FpaImubiasPayload) +{ + { + FpaImubiasPayload payload; + const char* msg = // clang-format off + "$FP,IMUBIAS,1,2342,321247.000000,2,1,1,3,0.008914,0.019806,0.150631,0.027202,0.010599,0.011393,0.00001,0.00001,0.00001,0.00001,0.00001,0.00001*4C\r\n"; // clang-format on + EXPECT_TRUE(payload.SetFromMsg((const uint8_t*)msg, strlen(msg))); + EXPECT_TRUE(payload.gps_time.week.valid); + EXPECT_EQ(payload.gps_time.week.value, 2342); + EXPECT_TRUE(payload.gps_time.tow.valid); + EXPECT_NEAR(payload.gps_time.tow.value, 321247.0, 1e-9); + EXPECT_EQ(payload.fusion_imu, FpaMeasStatus::DEGRADED); + EXPECT_EQ(payload.imu_status, FpaImuStatus::WARMSTARTED); + EXPECT_EQ(payload.imu_noise, FpaImuNoise::LOW_NOISE); + EXPECT_EQ(payload.imu_conv, FpaImuConv::WAIT_MOTION); + EXPECT_TRUE(payload.bias_acc.valid); + EXPECT_NEAR(payload.bias_acc.values[0], 0.008914, 1e-9); + EXPECT_NEAR(payload.bias_acc.values[1], 0.019806, 1e-9); + EXPECT_NEAR(payload.bias_acc.values[2], 0.150631, 1e-9); + EXPECT_TRUE(payload.bias_gyr.valid); + EXPECT_NEAR(payload.bias_gyr.values[0], 0.027202, 1e-9); + EXPECT_NEAR(payload.bias_gyr.values[1], 0.010599, 1e-9); + EXPECT_NEAR(payload.bias_gyr.values[2], 0.011393, 1e-9); + EXPECT_TRUE(payload.bias_cov_acc.valid); + EXPECT_NEAR(payload.bias_cov_acc.values[0], 0.00001, 1e-9); + EXPECT_NEAR(payload.bias_cov_acc.values[1], 0.00001, 1e-9); + EXPECT_NEAR(payload.bias_cov_acc.values[2], 0.00001, 1e-9); + EXPECT_TRUE(payload.bias_cov_gyr.valid); + EXPECT_NEAR(payload.bias_cov_gyr.values[0], 0.00001, 1e-9); + EXPECT_NEAR(payload.bias_cov_gyr.values[1], 0.00001, 1e-9); + EXPECT_NEAR(payload.bias_cov_gyr.values[2], 0.00001, 1e-9); + } + { + FpaImubiasPayload payload; + const char* msg = "$FP,IMUBIAS,1,2342,323844.000000,,,,,,,,,,,,,,,,*4C\r\n"; + EXPECT_TRUE(payload.SetFromMsg((const uint8_t*)msg, strlen(msg))); + EXPECT_TRUE(payload.gps_time.week.valid); + EXPECT_EQ(payload.gps_time.week.value, 2342); + EXPECT_TRUE(payload.gps_time.tow.valid); + EXPECT_NEAR(payload.gps_time.tow.value, 323844.0, 1e-9); + EXPECT_EQ(payload.fusion_imu, FpaMeasStatus::UNSPECIFIED); + EXPECT_EQ(payload.imu_status, FpaImuStatus::UNSPECIFIED); + EXPECT_EQ(payload.imu_noise, FpaImuNoise::UNSPECIFIED); + EXPECT_EQ(payload.imu_conv, FpaImuConv::UNSPECIFIED); + EXPECT_FALSE(payload.bias_acc.valid); + EXPECT_EQ(payload.bias_acc.values[0], 0.0); + EXPECT_EQ(payload.bias_acc.values[1], 0.0); + EXPECT_EQ(payload.bias_acc.values[2], 0.0); + EXPECT_FALSE(payload.bias_gyr.valid); + EXPECT_EQ(payload.bias_gyr.values[0], 0.0); + EXPECT_EQ(payload.bias_gyr.values[1], 0.0); + EXPECT_EQ(payload.bias_gyr.values[2], 0.0); + EXPECT_FALSE(payload.bias_cov_acc.valid); + EXPECT_EQ(payload.bias_cov_acc.values[0], 0.0); + EXPECT_EQ(payload.bias_cov_acc.values[1], 0.0); + EXPECT_EQ(payload.bias_cov_acc.values[2], 0.0); + EXPECT_FALSE(payload.bias_cov_gyr.valid); + EXPECT_EQ(payload.bias_cov_gyr.values[0], 0.0); + EXPECT_EQ(payload.bias_cov_gyr.values[1], 0.0); + EXPECT_EQ(payload.bias_cov_gyr.values[2], 0.0); + } +} + +// --------------------------------------------------------------------------------------------------------------------- + +TEST(FpaTest, FpaLlhPayload) +{ + { + FpaLlhPayload payload; + const char* msg = // clang-format off + "$FP,LLH,1,2231,227563.250000,47.392357470,8.448121451,473.5857,0.04533,0.03363,0.02884,0.00417,0.00086,-0.00136*62\r\n"; // clang-format on + EXPECT_TRUE(payload.SetFromMsg((const uint8_t*)msg, strlen(msg))); + EXPECT_TRUE(payload.gps_time.week.valid); + EXPECT_EQ(payload.gps_time.week.value, 2231); + EXPECT_TRUE(payload.gps_time.tow.valid); + EXPECT_NEAR(payload.gps_time.tow.value, 227563.250000, 1e-9); + EXPECT_TRUE(payload.llh.valid); + EXPECT_NEAR(payload.llh.values[0], 47.392357470, 1e-9); + EXPECT_NEAR(payload.llh.values[1], 8.448121451, 1e-9); + EXPECT_NEAR(payload.llh.values[2], 473.5857, 1e-9); + EXPECT_TRUE(payload.cov_enu.valid); + EXPECT_NEAR(payload.cov_enu.values[0], 0.04533, 1e-9); + EXPECT_NEAR(payload.cov_enu.values[1], 0.03363, 1e-9); + EXPECT_NEAR(payload.cov_enu.values[2], 0.02884, 1e-9); + EXPECT_NEAR(payload.cov_enu.values[3], 0.00417, 1e-9); + EXPECT_NEAR(payload.cov_enu.values[4], 0.00086, 1e-9); + EXPECT_NEAR(payload.cov_enu.values[5], -0.00136, 1e-9); + } + { + FpaLlhPayload payload; + const char* msg = "$FP,LLH,1,2231,227563.250000,,,,,,,,,*XX\r\n"; + EXPECT_TRUE(payload.SetFromMsg((const uint8_t*)msg, strlen(msg))); + EXPECT_TRUE(payload.gps_time.week.valid); + EXPECT_EQ(payload.gps_time.week.value, 2231); + EXPECT_TRUE(payload.gps_time.tow.valid); + EXPECT_NEAR(payload.gps_time.tow.value, 227563.250000, 1e-9); + EXPECT_FALSE(payload.llh.valid); + EXPECT_EQ(payload.llh.values[0], 0.0); + EXPECT_EQ(payload.llh.values[1], 0.0); + EXPECT_EQ(payload.llh.values[2], 0.0); + EXPECT_FALSE(payload.cov_enu.valid); + EXPECT_EQ(payload.cov_enu.values[0], 0.0); + EXPECT_EQ(payload.cov_enu.values[1], 0.0); + EXPECT_EQ(payload.cov_enu.values[2], 0.0); + EXPECT_EQ(payload.cov_enu.values[3], 0.0); + EXPECT_EQ(payload.cov_enu.values[4], 0.0); + EXPECT_EQ(payload.cov_enu.values[5], 0.0); + } +} + +// --------------------------------------------------------------------------------------------------------------------- + +TEST(FpaTest, FpaOdometryPayload) +{ + { + FpaOdometryPayload payload; + const char* msg = // clang-format off + "$FP,ODOMETRY,2,2231,227610.750000,4279243.1641,635824.2171,4671589.8683,-0.412792,0.290804,-0.123898,0.854216," + "-17.1078,-0.0526,-0.3252,0.02245,0.00275,0.10369,-1.0385,-1.3707,9.8249,4,1,8,8,1," + "0.01761,0.02274,0.01713,-0.00818,0.00235,0.00129,0.00013,0.00015,0.00014,-0.00001,0.00001,0.00002," + "0.03482,0.06244,0.05480,0.00096,0.00509,0.00054,fp_release_vr2_2.54.0_160*4F\r\n"; // clang-format on + EXPECT_TRUE(payload.SetFromMsg((const uint8_t*)msg, strlen(msg))); + EXPECT_EQ(payload.which, FpaOdomPayload::Which::FP_A_ODOMETRY); + EXPECT_TRUE(payload.gps_time.week.valid); + EXPECT_EQ(payload.gps_time.week.value, 2231); + EXPECT_TRUE(payload.gps_time.tow.valid); + EXPECT_NEAR(payload.gps_time.tow.value, 227610.750000, 1e-9); + EXPECT_TRUE(payload.pos.valid); + EXPECT_NEAR(payload.pos.values[0], 4279243.1641, 1e-9); + EXPECT_NEAR(payload.pos.values[1], 635824.2171, 1e-9); + EXPECT_NEAR(payload.pos.values[2], 4671589.8683, 1e-9); + EXPECT_TRUE(payload.orientation.valid); + EXPECT_NEAR(payload.orientation.values[0], -0.412792, 1e-9); + EXPECT_NEAR(payload.orientation.values[1], 0.290804, 1e-9); + EXPECT_NEAR(payload.orientation.values[2], -0.123898, 1e-9); + EXPECT_NEAR(payload.orientation.values[3], 0.854216, 1e-9); + EXPECT_TRUE(payload.vel.valid); + EXPECT_NEAR(payload.vel.values[0], -17.1078, 1e-9); + EXPECT_NEAR(payload.vel.values[1], -0.0526, 1e-9); + EXPECT_NEAR(payload.vel.values[2], -0.3252, 1e-9); + EXPECT_TRUE(payload.rot.valid); + EXPECT_NEAR(payload.rot.values[0], 0.02245, 1e-9); + EXPECT_NEAR(payload.rot.values[1], 0.00275, 1e-9); + EXPECT_NEAR(payload.rot.values[2], 0.10369, 1e-9); + EXPECT_TRUE(payload.acc.valid); + EXPECT_NEAR(payload.acc.values[0], -1.0385, 1e-9); + EXPECT_NEAR(payload.acc.values[1], -1.3707, 1e-9); + EXPECT_NEAR(payload.acc.values[2], 9.8249, 1e-9); + EXPECT_EQ(payload.fusion_status, FpaFusionStatusLegacy::VIO_GNSS); + EXPECT_EQ(payload.imu_bias_status, FpaImuStatusLegacy::CONVERGED); + EXPECT_EQ(payload.gnss1_fix, FpaGnssFix::RTK_FIXED); + EXPECT_EQ(payload.gnss2_fix, FpaGnssFix::RTK_FIXED); + EXPECT_EQ(payload.wheelspeed_status, FpaWsStatusLegacy::ONE_OR_MORE_CONVERGED); + EXPECT_TRUE(payload.pos_cov.valid); + EXPECT_NEAR(payload.pos_cov.values[0], 0.01761, 1e-9); + EXPECT_NEAR(payload.pos_cov.values[1], 0.02274, 1e-9); + EXPECT_NEAR(payload.pos_cov.values[2], 0.01713, 1e-9); + EXPECT_NEAR(payload.pos_cov.values[3], -0.00818, 1e-9); + EXPECT_NEAR(payload.pos_cov.values[4], 0.00235, 1e-9); + EXPECT_NEAR(payload.pos_cov.values[5], 0.00129, 1e-9); + EXPECT_TRUE(payload.orientation_cov.valid); + EXPECT_NEAR(payload.orientation_cov.values[0], 0.00013, 1e-9); + EXPECT_NEAR(payload.orientation_cov.values[1], 0.00015, 1e-9); + EXPECT_NEAR(payload.orientation_cov.values[2], 0.00014, 1e-9); + EXPECT_NEAR(payload.orientation_cov.values[3], -0.00001, 1e-9); + EXPECT_NEAR(payload.orientation_cov.values[4], 0.00001, 1e-9); + EXPECT_NEAR(payload.orientation_cov.values[5], 0.00002, 1e-9); + EXPECT_TRUE(payload.vel_cov.valid); + EXPECT_NEAR(payload.vel_cov.values[0], 0.03482, 1e-9); + EXPECT_NEAR(payload.vel_cov.values[1], 0.06244, 1e-9); + EXPECT_NEAR(payload.vel_cov.values[2], 0.05480, 1e-9); + EXPECT_NEAR(payload.vel_cov.values[3], 0.00096, 1e-9); + EXPECT_NEAR(payload.vel_cov.values[4], 0.00509, 1e-9); + EXPECT_NEAR(payload.vel_cov.values[5], 0.00054, 1e-9); + } +} + +// --------------------------------------------------------------------------------------------------------------------- + +TEST(FpaTest, FpaOdomenuPayload) +{ + { + FpaOdomenuPayload payload; + const char* msg = // clang-format off + "$FP,ODOMENU,1,2180,298591.500000,-1.8339,2.6517,-0.0584,0.556794,-0.042551,-0.007850,0.829523,2.2993," + "-1.6994,-0.0222,0.20063,0.08621,-1.21972,-3.6947,-3.3827,9.7482,4,1,8,8,1,0.00415,0.00946,0.00746," + "-0.00149,-0.00084,0.00025,0.00003,0.00003,0.00012,0.00000,0.00000,0.00000,0.01742,0.01146,0.01612," + "-0.00550,-0.00007,-0.00050*74\r\n"; // clang-format on + EXPECT_TRUE(payload.SetFromMsg((const uint8_t*)msg, strlen(msg))); + EXPECT_EQ(payload.which, FpaOdomPayload::Which::FP_A_ODOMENU); + EXPECT_TRUE(payload.gps_time.week.valid); + EXPECT_EQ(payload.gps_time.week.value, 2180); + EXPECT_TRUE(payload.gps_time.tow.valid); + EXPECT_NEAR(payload.gps_time.tow.value, 298591.500000, 1e-9); + } +} + +// --------------------------------------------------------------------------------------------------------------------- + +TEST(FpaTest, FpaOdomshPayload) +{ + { + FpaOdomshPayload payload; + const char* msg = // clang-format off + "$FP,ODOMSH,1,2180,298591.500000,-1.8339,2.6517,-0.0584,0.556794,-0.042551,-0.007850,0.829523,2.2993," + "-1.6994,-0.0222,0.20063,0.08621,-1.21972,-3.6947,-3.3827,9.7482,4,1,8,8,1,0.00415,0.00946,0.00746," + "-0.00149,-0.00084,0.00025,0.00003,0.00003,0.00012,0.00000,0.00000,0.00000,0.01742,0.01146,0.01612," + "-0.00550,-0.00007,-0.00050*74\r\n"; // clang-format on + EXPECT_TRUE(payload.SetFromMsg((const uint8_t*)msg, strlen(msg))); + EXPECT_EQ(payload.which, FpaOdomPayload::Which::FP_A_ODOMSH); + EXPECT_TRUE(payload.gps_time.week.valid); + EXPECT_EQ(payload.gps_time.week.value, 2180); + EXPECT_TRUE(payload.gps_time.tow.valid); + EXPECT_NEAR(payload.gps_time.tow.value, 298591.500000, 1e-9); + } +} + +// --------------------------------------------------------------------------------------------------------------------- + +TEST(FpaTest, FpaOdomstatusPayload) +{ + { + FpaOdomstatusPayload payload; + const char* msg = // clang-format off + "$FP,ODOMSTATUS,1,2342,321241.350000,2,2,1,1,1,1,,0,,,,,,1,1,3,8,8,3,5,5,,0,6,,,,,,,,,,,,*24\r\n"; // clang-format on + EXPECT_TRUE(payload.SetFromMsg((const uint8_t*)msg, strlen(msg))); + EXPECT_TRUE(payload.gps_time.week.valid); + EXPECT_EQ(payload.gps_time.week.value, 2342); + EXPECT_TRUE(payload.gps_time.tow.valid); + EXPECT_NEAR(payload.gps_time.tow.value, 321241.350000, 1e-9); + EXPECT_EQ(payload.init_status, FpaInitStatus::GLOBAL_INIT); + EXPECT_EQ(payload.fusion_imu, FpaMeasStatus::DEGRADED); + EXPECT_EQ(payload.fusion_gnss1, FpaMeasStatus::USED); + EXPECT_EQ(payload.fusion_gnss2, FpaMeasStatus::USED); + EXPECT_EQ(payload.fusion_corr, FpaMeasStatus::USED); + EXPECT_EQ(payload.fusion_cam1, FpaMeasStatus::USED); + EXPECT_EQ(payload.fusion_ws, FpaMeasStatus::NOT_USED); + EXPECT_EQ(payload.fusion_markers, FpaMeasStatus::UNSPECIFIED); + EXPECT_EQ(payload.imu_status, FpaImuStatus::WARMSTARTED); + EXPECT_EQ(payload.imu_noise, FpaImuNoise::LOW_NOISE); + EXPECT_EQ(payload.imu_conv, FpaImuConv::WAIT_MOTION); + EXPECT_EQ(payload.gnss1_status, FpaGnssStatus::RTK_FIXED); + EXPECT_EQ(payload.gnss2_status, FpaGnssStatus::RTK_FIXED); + EXPECT_EQ(payload.baseline_status, FpaBaselineStatus::PASSING); + EXPECT_EQ(payload.corr_status, FpaCorrStatus::GOOD_CORR); + EXPECT_EQ(payload.cam1_status, FpaCamStatus::GOOD); + EXPECT_EQ(payload.ws_status, FpaWsStatus::NOT_ENABLED); + EXPECT_EQ(payload.ws_conv, FpaWsConv::IDLE); + EXPECT_EQ(payload.markers_status, FpaMarkersStatus::UNSPECIFIED); + EXPECT_EQ(payload.markers_conv, FpaMarkersConv::UNSPECIFIED); + } + { + FpaOdomstatusPayload payload; + const char* msg = "$FP,ODOMSTATUS,1,2342,324917.700000,,,,,,,,,,,,,,,,,,,,,,,,,,,,,,,,,,,,*1E\r\n"; + EXPECT_TRUE(payload.SetFromMsg((const uint8_t*)msg, strlen(msg))); + EXPECT_TRUE(payload.gps_time.week.valid); + EXPECT_EQ(payload.gps_time.week.value, 2342); + EXPECT_TRUE(payload.gps_time.tow.valid); + EXPECT_NEAR(payload.gps_time.tow.value, 324917.700000, 1e-9); + EXPECT_EQ(payload.init_status, FpaInitStatus::UNSPECIFIED); + EXPECT_EQ(payload.fusion_imu, FpaMeasStatus::UNSPECIFIED); + EXPECT_EQ(payload.fusion_gnss1, FpaMeasStatus::UNSPECIFIED); + EXPECT_EQ(payload.fusion_gnss2, FpaMeasStatus::UNSPECIFIED); + EXPECT_EQ(payload.fusion_corr, FpaMeasStatus::UNSPECIFIED); + EXPECT_EQ(payload.fusion_cam1, FpaMeasStatus::UNSPECIFIED); + EXPECT_EQ(payload.fusion_ws, FpaMeasStatus::UNSPECIFIED); + EXPECT_EQ(payload.fusion_markers, FpaMeasStatus::UNSPECIFIED); + EXPECT_EQ(payload.imu_status, FpaImuStatus::UNSPECIFIED); + EXPECT_EQ(payload.imu_noise, FpaImuNoise::UNSPECIFIED); + EXPECT_EQ(payload.imu_conv, FpaImuConv::UNSPECIFIED); + EXPECT_EQ(payload.gnss1_status, FpaGnssStatus::UNSPECIFIED); + EXPECT_EQ(payload.gnss2_status, FpaGnssStatus::UNSPECIFIED); + EXPECT_EQ(payload.baseline_status, FpaBaselineStatus::UNSPECIFIED); + EXPECT_EQ(payload.corr_status, FpaCorrStatus::UNSPECIFIED); + EXPECT_EQ(payload.cam1_status, FpaCamStatus::UNSPECIFIED); + EXPECT_EQ(payload.ws_status, FpaWsStatus::UNSPECIFIED); + EXPECT_EQ(payload.ws_conv, FpaWsConv::UNSPECIFIED); + EXPECT_EQ(payload.markers_status, FpaMarkersStatus::UNSPECIFIED); + EXPECT_EQ(payload.markers_conv, FpaMarkersConv::UNSPECIFIED); + } +} + +// --------------------------------------------------------------------------------------------------------------------- + +TEST(FpaTest, FpaTextPayload) +{ + { + FpaTextPayload payload; + const char* msg = "$FP,TEXT,1,INFO,Fixposition AG - www.fixposition.com*09\r\n"; + EXPECT_TRUE(payload.SetFromMsg((const uint8_t*)msg, strlen(msg))); + EXPECT_EQ(payload.level, FpaTextLevel::INFO); + EXPECT_EQ(std::string(payload.text), "Fixposition AG - www.fixposition.com"); + } + { + FpaTextPayload payload; + const char* msg = "$FP,TEXT,1,NOPE,blabla*09\r\n"; + EXPECT_FALSE(payload.SetFromMsg((const uint8_t*)msg, strlen(msg))); + EXPECT_EQ(payload.level, FpaTextLevel::UNSPECIFIED); + EXPECT_EQ(payload.text[0], '\0'); + } +} + +// --------------------------------------------------------------------------------------------------------------------- + +TEST(FpaTest, FpaTfPayload) +{ + { + FpaTfPayload payload; + const char* msg = // clang-format off + "$FP,TF,2,2233,315835.000000,VRTK,CAM,-0.00000,-0.00000,-0.00000,1.000000,0.000000,0.000000,0.000000*6B\r\n"; // clang-format on + EXPECT_TRUE(payload.SetFromMsg((const uint8_t*)msg, strlen(msg))); + EXPECT_EQ(payload.gps_time.week.value, 2233); + EXPECT_TRUE(payload.gps_time.tow.valid); + EXPECT_NEAR(payload.gps_time.tow.value, 315835.000000, 1e-9); + EXPECT_EQ(std::string(payload.frame_a), "VRTK"); + EXPECT_EQ(std::string(payload.frame_b), "CAM"); + EXPECT_TRUE(payload.translation.valid); + EXPECT_NEAR(payload.translation.values[0], 0.0, 1e-9); + EXPECT_NEAR(payload.translation.values[1], 0.0, 1e-9); + EXPECT_NEAR(payload.translation.values[2], 0.0, 1e-9); + EXPECT_TRUE(payload.orientation.valid); + EXPECT_NEAR(payload.orientation.values[0], 1.0, 1e-9); + EXPECT_NEAR(payload.orientation.values[1], 0.0, 1e-9); + EXPECT_NEAR(payload.orientation.values[2], 0.0, 1e-9); + EXPECT_NEAR(payload.orientation.values[3], 0.0, 1e-9); + } +} + +// --------------------------------------------------------------------------------------------------------------------- + +TEST(FpaTest, FpaTpPayload) +{ + { + FpaTpPayload payload; + const char* msg = "$FP,TP,1,GNSS1,UTC,USNO,195391,0.000000000000,18*4F\r\n"; + EXPECT_TRUE(payload.SetFromMsg((const uint8_t*)msg, strlen(msg))); + EXPECT_EQ(std::string(payload.tp_name), "GNSS1"); + EXPECT_EQ(payload.timebase, FpaTimebase::UTC); + EXPECT_EQ(payload.timeref, FpaTimeref::UTC_USNO); + EXPECT_TRUE(payload.tp_tow_sec.valid); + EXPECT_EQ(payload.tp_tow_sec.value, 195391); + EXPECT_TRUE(payload.tp_tow_psec.valid); + EXPECT_NEAR(payload.tp_tow_psec.value, 0.0, 1e-10); + EXPECT_TRUE(payload.gps_leaps.valid); + EXPECT_EQ(payload.gps_leaps.value, 18); + } +} + +/* ****************************************************************************************************************** */ +} // namespace + +int main(int argc, char** argv) +{ + testing::InitGoogleTest(&argc, argv); + auto level = fpsdk::common::logging::LoggingLevel::WARNING; + for (int ix = 0; ix < argc; ix++) { + if ((argv[ix][0] == '-') && argv[ix][1] == 'v') { + level++; + } + } + fpsdk::common::logging::LoggingSetParams(level); + return RUN_ALL_TESTS(); +} diff --git a/fpsdk_common/test/parser_fpb_test.cpp b/fpsdk_common/test/parser_fpb_test.cpp new file mode 100644 index 0000000..b50db21 --- /dev/null +++ b/fpsdk_common/test/parser_fpb_test.cpp @@ -0,0 +1,203 @@ +/** + * \verbatim + * ___ ___ + * \ \ / / + * \ \/ / Copyright (c) Fixposition AG (www.fixposition.com) and contributors + * / /\ \ License: see the LICENSE file + * /__/ \__\ + * \endverbatim + * + * @file + * @brief Fixposition SDK: tests for fpsdk::common::parser::fpb + */ + +/* LIBC/STL */ +#include +#include + +/* EXTERNAL */ +#include + +/* PACKAGE */ +#include +#include +#include + +namespace { +/* ****************************************************************************************************************** */ +using namespace fpsdk::common::parser; +using namespace fpsdk::common::parser::fpb; + +TEST(ParserFpbTest, Macros) +{ + const uint8_t msg[] = { 0x55, 0x55, 0x34, 0x12, 0x55, 0x55, 0x55, 0x55, 0xaa, 0xaa, 0xaa, 0xaa }; + ASSERT_EQ(FpbMsgId(msg), 0x1234); +} + +// --------------------------------------------------------------------------------------------------------------------- + +TEST(ParserFpbTest, FpbGetMessageName) +{ + // Known message + { + const uint8_t msg[] = { // clang-format off + FP_B_SYNC_1, FP_B_SYNC_2, + (uint8_t)(FP_B_UNITTEST1_MSGID & 0xff), (uint8_t)((FP_B_UNITTEST1_MSGID >> 8) & 0xff), + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00 }; // clang-format on + char str[100]; + EXPECT_TRUE(FpbGetMessageName(str, sizeof(str), msg, sizeof(msg))); + EXPECT_EQ(std::string(str), std::string("FP_B-UNITTEST1")); + } + // Unknown message + { + const uint8_t msg[] = { // clang-format off + FP_B_SYNC_1, FP_B_SYNC_2, + 0xdc, 0xfe, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00 }; // clang-format on + char str[100]; + EXPECT_TRUE(FpbGetMessageName(str, sizeof(str), msg, sizeof(msg))); + EXPECT_EQ(std::string(str), std::string("FP_B-MSG65244")); + } + + // Bad arguments + { + const uint8_t msg[] = { // clang-format off + FP_B_SYNC_1, FP_B_SYNC_2, 0x34, 0x12, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00 }; // clang-format on + char str[100]; + EXPECT_FALSE(FpbGetMessageName(str, 0, msg, sizeof(msg))); + EXPECT_FALSE(FpbGetMessageName(str, -1, msg, sizeof(msg))); + EXPECT_FALSE(FpbGetMessageName(NULL, 10, msg, sizeof(msg))); + EXPECT_FALSE(FpbGetMessageName(NULL, 0, msg, sizeof(msg))); + EXPECT_FALSE(FpbGetMessageName(NULL, -1, msg, sizeof(msg))); + EXPECT_FALSE(FpbGetMessageName(str, sizeof(str), msg, 0)); + EXPECT_FALSE(FpbGetMessageName(str, sizeof(str), msg, 5)); + EXPECT_FALSE(FpbGetMessageName(str, sizeof(str), NULL, sizeof(msg))); + } + + // Too small string is cut + { + const uint8_t msg[] = { // clang-format off + FP_B_SYNC_1, FP_B_SYNC_2, + (uint8_t)(FP_B_UNITTEST1_MSGID & 0xff), (uint8_t)((FP_B_UNITTEST1_MSGID >> 8) & 0xff), + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00 }; // clang-format on + char str[10]; + EXPECT_FALSE(FpbGetMessageName(str, sizeof(str), msg, sizeof(msg))); + EXPECT_EQ(std::string(str), std::string("FP_B-UNIT")); + } +} + +// --------------------------------------------------------------------------------------------------------------------- + +TEST(ParserFpbTest, FpbMakeMessage) +{ + for (const int payload_size : + { 0, 1, 2, 3, 4, 5, 6, 7, 8, 100, 200, 500, 1000, 2000, (int)(MAX_FP_B_SIZE - FP_B_FRAME_SIZE) }) { + // Create payload with this many bytes of data + std::vector payload; + for (int ix = 0; ix < payload_size; ix++) { + payload.push_back((uint8_t)(ix + 1)); + } + + // We expect a message of this size + const int msg_size = payload_size + FP_B_FRAME_SIZE; + + // Create message + std::vector msg; + EXPECT_TRUE(FpbMakeMessage(msg, FP_B_UNITTEST2_MSGID, 0, payload)); + EXPECT_EQ((int)msg.size(), msg_size); + + // Create message using "raw" API + std::vector msg2; + EXPECT_TRUE(FpbMakeMessage(msg2, FP_B_UNITTEST2_MSGID, 0, payload.data(), (int)payload.size())); + EXPECT_EQ(msg.size(), msg2.size()); + EXPECT_EQ(std::memcmp(msg.data(), msg2.data(), msg.size()), 0); + + // Run it through the parser and check that it is still the same + Parser parser; + parser.Add(msg); + ParserMsg parser_msg; + EXPECT_TRUE(parser.Process(parser_msg)); + EXPECT_EQ(parser_msg.data_.size(), FP_B_FRAME_SIZE + payload.size()); + EXPECT_EQ(std::string(parser_msg.name_), std::string("FP_B-UNITTEST2")); + // Payload should be the same + EXPECT_TRUE(std::memcmp(payload.data(), &parser_msg.data_[FP_B_HEAD_SIZE], payload.size()) == 0); + + // There should be nothing left in the parser + EXPECT_FALSE(parser.Flush(parser_msg)); + } + + // Too large (by one byte) + { + std::vector payload(MAX_FP_B_SIZE - FP_B_FRAME_SIZE + 1); + std::vector msg; + EXPECT_FALSE(FpbMakeMessage(msg, FP_B_UNITTEST2_MSGID, 0, payload)); + EXPECT_EQ(msg.size(), (std::size_t)0); + EXPECT_FALSE(FpbMakeMessage(msg, FP_B_UNITTEST2_MSGID, 0, payload.data(), payload.size())); + EXPECT_EQ(msg.size(), (std::size_t)0); + } + + // Combinations of arguments + { + const uint8_t payload[] = { 0x55, 0x55 }; + std::vector msg; + // These are okay: + EXPECT_TRUE(FpbMakeMessage(msg, FP_B_UNITTEST2_MSGID, 0, payload, 0)); + EXPECT_EQ(msg.size(), (std::size_t)FP_B_FRAME_SIZE); + msg.clear(); + EXPECT_TRUE(FpbMakeMessage(msg, FP_B_UNITTEST2_MSGID, 0, NULL, 0)); + EXPECT_EQ(msg.size(), (std::size_t)FP_B_FRAME_SIZE); + // But these are bad: + msg.clear(); + EXPECT_FALSE(FpbMakeMessage(msg, FP_B_UNITTEST2_MSGID, 0, payload, -1)); + EXPECT_EQ(msg.size(), (std::size_t)0); + EXPECT_FALSE(FpbMakeMessage(msg, FP_B_UNITTEST2_MSGID, 0, NULL, 1)); + EXPECT_EQ(msg.size(), (std::size_t)0); + EXPECT_FALSE(FpbMakeMessage(msg, FP_B_UNITTEST2_MSGID, 0, NULL, -1)); + EXPECT_EQ(msg.size(), (std::size_t)0); + } + + // Message time + { + std::vector msg; + EXPECT_TRUE(FpbMakeMessage(msg, FP_B_UNITTEST1_MSGID, 0x1234, NULL, 0)); + EXPECT_EQ(msg.size(), (std::size_t)FP_B_FRAME_SIZE); + EXPECT_EQ(msg[6], 0x34); + EXPECT_EQ(msg[7], 0x12); + EXPECT_EQ(FpbMsgTime(msg.data()), 0x1234); + } + + // Example in docu + { + std::vector msg; + const uint8_t payload[] = { 0x01, 0x02, 0x03, 0x04 }; + EXPECT_TRUE(FpbMakeMessage(msg, 0x1234, 0x4321, payload, sizeof(payload))); + EXPECT_EQ(msg.size(), (std::size_t)FP_B_FRAME_SIZE + sizeof(payload)); + EXPECT_EQ(msg, std::vector({ 0x66, 0x21, 0x34, 0x12, 0x04, 0x00, 0x21, 0x43, 0x01, 0x02, 0x03, 0x04, + 0x61, 0xc4, 0xc5, 0x9c })); + } + + // FP_B-VERSION + { + std::vector msg; + EXPECT_TRUE(FpbMakeMessage(msg, FP_B_VERSION_MSGID, 0x0000, NULL, 0)); + EXPECT_EQ(msg.size(), (std::size_t)FP_B_FRAME_SIZE); + EXPECT_EQ(FpbMsgTime(msg.data()), 0x0000); + DEBUG_HEXDUMP(msg.data(), msg.size(), NULL, "FP_B-VERSION poll"); + } +} + +/* ****************************************************************************************************************** */ +} // namespace + +int main(int argc, char** argv) +{ + testing::InitGoogleTest(&argc, argv); + auto level = fpsdk::common::logging::LoggingLevel::WARNING; + for (int ix = 0; ix < argc; ix++) { + if ((argv[ix][0] == '-') && argv[ix][1] == 'v') { + level++; + } + } + fpsdk::common::logging::LoggingSetParams(level); + return RUN_ALL_TESTS(); +} diff --git a/fpsdk_common/test/parser_nmea_test.cpp b/fpsdk_common/test/parser_nmea_test.cpp new file mode 100644 index 0000000..b60ec4e --- /dev/null +++ b/fpsdk_common/test/parser_nmea_test.cpp @@ -0,0 +1,945 @@ +/** + * \verbatim + * ___ ___ + * \ \ / / + * \ \/ / Copyright (c) Fixposition AG (www.fixposition.com) and contributors + * / /\ \ License: see the LICENSE file + * /__/ \__\ + * \endverbatim + * + * @file + * @brief Fixposition SDK: tests for fpsdk::common::parser::nmea + */ + +/* LIBC/STL */ +#include + +/* EXTERNAL */ +#include + +/* PACKAGE */ +#include +#include + +namespace { +/* ****************************************************************************************************************** */ +using namespace fpsdk::common::parser::nmea; + +TEST(ParserNmeaTest, NmeaGetMessageMeta) +{ + // Standard NMEA + { + // 012345678901234567890123456789 + // TTFFF PPPPPPPPPPP + const char* msg = "$GNGGA,123,456,789*xx\r\n"; + NmeaMessageMeta meta; + EXPECT_TRUE(NmeaGetMessageMeta(meta, (const uint8_t*)msg, strlen(msg))) << msg; + EXPECT_EQ(std::string(meta.talker_), std::string("GN")) << msg; + EXPECT_EQ(std::string(meta.formatter_), std::string("GGA")) << msg; + EXPECT_EQ(meta.payload_ix0_, 7) << msg; + EXPECT_EQ(meta.payload_ix1_, 17) << msg; + } + + // u-blox proprietary + { + // 012345678901234567890123456789 + // TFFF PPPPPPPPPPPPPP + const char* msg = "$PUBX,nn,123,456,789*xx\r\n"; + NmeaMessageMeta meta; + EXPECT_TRUE(NmeaGetMessageMeta(meta, (const uint8_t*)msg, strlen(msg))) << msg; + EXPECT_EQ(std::string(meta.talker_), std::string("P")) << msg; + EXPECT_EQ(std::string(meta.formatter_), std::string("UBX")) << msg; + EXPECT_EQ(meta.payload_ix0_, 6) << msg; + EXPECT_EQ(meta.payload_ix1_, 19) << msg; + } + + // Fixposition proprietary (FP_A). Compare tests for FpaGetMessageMeta + { + // 012345678901234567890123456789 + // TT,PPPPPPPPPPPPPPPPPPPPPP + const char* msg = "$FP,ODOMETRY,n,...,...,...*xx\r\n"; + NmeaMessageMeta meta; + EXPECT_TRUE(NmeaGetMessageMeta(meta, (const uint8_t*)msg, strlen(msg))) << msg; + EXPECT_EQ(std::string(meta.talker_), std::string("FP")) << msg; + EXPECT_EQ(std::string(meta.formatter_), std::string("")) << msg; + EXPECT_EQ(meta.payload_ix0_, 4) << msg; + EXPECT_EQ(meta.payload_ix1_, 25) << msg; + } + + // Empty NMEA message + { + // 012345678901234567890123456789 + // TFFFF + const char* msg = "$GPGGA*xx\r\n"; + NmeaMessageMeta meta; + EXPECT_TRUE(NmeaGetMessageMeta(meta, (const uint8_t*)msg, strlen(msg))) << msg; + EXPECT_EQ(std::string(meta.talker_), std::string("GP")) << msg; + EXPECT_EQ(std::string(meta.formatter_), std::string("GGA")) << msg; + EXPECT_EQ(meta.payload_ix0_, 0) << msg; + EXPECT_EQ(meta.payload_ix1_, 0) << msg; + } + + // Bad input + { + const char* msg = "whateverwhatever"; + NmeaMessageMeta meta; + EXPECT_FALSE(NmeaGetMessageMeta(meta, NULL, 0)) << msg; + EXPECT_FALSE(NmeaGetMessageMeta(meta, NULL, -1)) << msg; + EXPECT_FALSE(NmeaGetMessageMeta(meta, (const uint8_t*)msg, 0)) << msg; + EXPECT_FALSE(NmeaGetMessageMeta(meta, (const uint8_t*)msg, -1)) << msg; + } + { + const char* msg = "$ABCDEFGHIJKLMNOP"; + NmeaMessageMeta meta; + EXPECT_FALSE(NmeaGetMessageMeta(meta, (const uint8_t*)msg, strlen(msg))); + } + { + const char* msg = "$GNABCDEFGHIJKLMNOPQRSTUVW,123,456,789*xx\r\n"; + NmeaMessageMeta meta; + EXPECT_FALSE(NmeaGetMessageMeta(meta, (const uint8_t*)msg, strlen(msg))) << msg; + EXPECT_EQ(std::string(meta.talker_), std::string("GN")) << msg; + EXPECT_EQ(std::string(meta.formatter_), std::string("")) << msg; + EXPECT_EQ(meta.payload_ix0_, 0) << msg; + EXPECT_EQ(meta.payload_ix1_, 0) << msg; + } +} + +// --------------------------------------------------------------------------------------------------------------------- + +TEST(ParserNmeaTest, NmeaGetMessageName) +{ + // Standard NMEA + { + const char* msg = "$GNGGA,123,456,789*xx\r\n"; + char name[100]; + EXPECT_TRUE(NmeaGetMessageName(name, sizeof(name), (const uint8_t*)msg, strlen(msg))) << msg; + EXPECT_EQ(std::string(name), std::string("NMEA-GN-GGA")) << msg; + } + + // u-blox proprietary + { + const char* msg = "$PUBX,41,123,456,789*xx\r\n"; + char name[100]; + EXPECT_TRUE(NmeaGetMessageName(name, sizeof(name), (const uint8_t*)msg, strlen(msg))) << msg; + EXPECT_EQ(std::string(name), std::string("NMEA-PUBX-CONFIG")) << msg; + } + { + const char* msg = "$PUBX,00,123,456,789*xx\r\n"; + char name[100]; + EXPECT_TRUE(NmeaGetMessageName(name, sizeof(name), (const uint8_t*)msg, strlen(msg))) << msg; + EXPECT_EQ(std::string(name), std::string("NMEA-PUBX-POSITION")) << msg; + } + { + const char* msg = "$PUBX,40,123,456,789*xx\r\n"; + char name[100]; + EXPECT_TRUE(NmeaGetMessageName(name, sizeof(name), (const uint8_t*)msg, strlen(msg))) << msg; + EXPECT_EQ(std::string(name), std::string("NMEA-PUBX-RATE")) << msg; + } + { + const char* msg = "$PUBX,03,123,456,789*xx\r\n"; + char name[100]; + EXPECT_TRUE(NmeaGetMessageName(name, sizeof(name), (const uint8_t*)msg, strlen(msg))) << msg; + EXPECT_EQ(std::string(name), std::string("NMEA-PUBX-SVSTATUS")) << msg; + } + { + const char* msg = "$PUBX,04,123,456,789*xx\r\n"; + char name[100]; + EXPECT_TRUE(NmeaGetMessageName(name, sizeof(name), (const uint8_t*)msg, strlen(msg))) << msg; + EXPECT_EQ(std::string(name), std::string("NMEA-PUBX-TIME")) << msg; + } + { + const char* msg = "$PUBX,99,123,456,789*xx\r\n"; + char name[100]; + EXPECT_TRUE(NmeaGetMessageName(name, sizeof(name), (const uint8_t*)msg, strlen(msg))) << msg; + EXPECT_EQ(std::string(name), std::string("NMEA-PUBX-99")) << msg; + } + { + const char* msg = "$PUBX,42,123,456,789*xx\r\n"; + char name[100]; + EXPECT_TRUE(NmeaGetMessageName(name, sizeof(name), (const uint8_t*)msg, strlen(msg))) << msg; + EXPECT_EQ(std::string(name), std::string("NMEA-PUBX-42")) << msg; + } + { + const char* msg = "$PUBX,01,123,456,789*xx\r\n"; + char name[100]; + EXPECT_TRUE(NmeaGetMessageName(name, sizeof(name), (const uint8_t*)msg, strlen(msg))) << msg; + EXPECT_EQ(std::string(name), std::string("NMEA-PUBX-01")) << msg; + } + // Bad u-blox proprietary + { + const char* msg = "$PUBXX,00,123,456,789*xx\r\n"; + char name[100]; + EXPECT_TRUE(NmeaGetMessageName(name, sizeof(name), (const uint8_t*)msg, strlen(msg))) << msg; + EXPECT_EQ(std::string(name), std::string("NMEA-P-UBXX")) << msg; + } + { + const char* msg = "$PVBX,00,123,456,789*xx\r\n"; + char name[100]; + EXPECT_TRUE(NmeaGetMessageName(name, sizeof(name), (const uint8_t*)msg, strlen(msg))) << msg; + EXPECT_EQ(std::string(name), std::string("NMEA-P-VBX")) << msg; + } + { + const char* msg = "$PUCX,00,123,456,789*xx\r\n"; + char name[100]; + EXPECT_TRUE(NmeaGetMessageName(name, sizeof(name), (const uint8_t*)msg, strlen(msg))) << msg; + EXPECT_EQ(std::string(name), std::string("NMEA-P-UCX")) << msg; + } + { + const char* msg = "$PUBY,00,123,456,789*xx\r\n"; + char name[100]; + EXPECT_TRUE(NmeaGetMessageName(name, sizeof(name), (const uint8_t*)msg, strlen(msg))) << msg; + EXPECT_EQ(std::string(name), std::string("NMEA-P-UBY")) << msg; + } + + // Other NMEA proprietary + { + const char* msg = "$PABC,123,456,789*xx\r\n"; + char name[100]; + EXPECT_TRUE(NmeaGetMessageName(name, sizeof(name), (const uint8_t*)msg, strlen(msg))) << msg; + EXPECT_EQ(std::string(name), std::string("NMEA-P-ABC")) << msg; + } + + // Fixposition proprietary (FP_A) + { + const char* msg = "$FP,ODOMETRY,n,...,...,...*xx\r\n"; + char name[100]; + EXPECT_TRUE(NmeaGetMessageName(name, sizeof(name), (const uint8_t*)msg, strlen(msg))) << msg; + EXPECT_EQ(std::string(name), std::string("NMEA-FP-?")) << msg; + // EXPECT_FALSE(NmeaGetMessageName(name, 10, (const uint8_t*)msg, strlen(msg))) << msg; + } + // Bad FP_A + { + const char* msg = "$GP,ODOMETRY,n,...,...,...*xx\r\n"; + char name[100]; + EXPECT_TRUE(NmeaGetMessageName(name, sizeof(name), (const uint8_t*)msg, strlen(msg))) << msg; + EXPECT_EQ(std::string(name), std::string("NMEA-GP-?")) << msg; + } + { + const char* msg = "$FQ,ODOMETRY,n,...,...,...*xx\r\n"; + char name[100]; + EXPECT_TRUE(NmeaGetMessageName(name, sizeof(name), (const uint8_t*)msg, strlen(msg))) << msg; + EXPECT_EQ(std::string(name), std::string("NMEA-FQ-?")) << msg; + } + { + const char* msg = "$FPP,ODOMETRY,n,...,...,...*xx\r\n"; + char name[100]; + EXPECT_TRUE(NmeaGetMessageName(name, sizeof(name), (const uint8_t*)msg, strlen(msg))) << msg; + EXPECT_EQ(std::string(name), std::string("NMEA-FP-P")) << msg; + } + + // Empty NMEA message + { + const char* msg = "$GPGGA*xx\r\n"; + char name[100]; + EXPECT_TRUE(NmeaGetMessageName(name, sizeof(name), (const uint8_t*)msg, strlen(msg))) << msg; + EXPECT_EQ(std::string(name), std::string("NMEA-GP-GGA")) << msg; + } + + // Bad input + { + const char* msg = "whateverwhatever"; + char name[100]; + EXPECT_FALSE(NmeaGetMessageName(name, sizeof(name), NULL, 0)) << msg; + EXPECT_FALSE(NmeaGetMessageName(name, sizeof(name), NULL, -1)) << msg; + EXPECT_FALSE(NmeaGetMessageName(name, sizeof(name), (const uint8_t*)msg, 0)) << msg; + EXPECT_FALSE(NmeaGetMessageName(name, sizeof(name), (const uint8_t*)msg, -1)) << msg; + EXPECT_FALSE(NmeaGetMessageName(NULL, 0, (const uint8_t*)msg, sizeof(msg))) << msg; + EXPECT_FALSE(NmeaGetMessageName(NULL, -1, (const uint8_t*)msg, sizeof(msg))) << msg; + EXPECT_FALSE(NmeaGetMessageName(name, 0, (const uint8_t*)msg, sizeof(msg))) << msg; + EXPECT_FALSE(NmeaGetMessageName(name, -1, (const uint8_t*)msg, sizeof(msg))) << msg; + EXPECT_FALSE(NmeaGetMessageName(NULL, 0, NULL, 0)) << msg; + EXPECT_FALSE(NmeaGetMessageName(NULL, 0, NULL, -1)) << msg; + } + + // Too small string is cut + { + const char* msg = "$GPGGA*xx\r\n"; + char name[10]; + EXPECT_FALSE(NmeaGetMessageName(name, sizeof(name), (const uint8_t*)msg, strlen(msg))) << msg; + EXPECT_EQ(std::string(name), std::string("NMEA-GP-G")) << msg; + } +} + +// --------------------------------------------------------------------------------------------------------------------- + +TEST(NmeaTest, NmeaTime) +{ + const NmeaTime t1 = { true, 11, 44, 1.0 }; + EXPECT_TRUE(t1.valid); + EXPECT_EQ(t1.hours, 11); + EXPECT_EQ(t1.mins, 44); + EXPECT_NEAR(t1.secs, 1.0, 1e-9); + const NmeaTime t1copy = t1; + const NmeaTime t2 = { true, 11, 44, 2.0 }; + const NmeaTime t3 = { true, 11, 44, 2.0 + DBL_EPSILON }; + const NmeaTime t4 = { true, 11, 44, 2.00000001 }; + const NmeaTime t5 = { false, 11, 44, 2.00000001 }; + EXPECT_FALSE(t5.valid); + EXPECT_EQ(t1, t1copy); + EXPECT_NE(t1, t2); + EXPECT_EQ(t2, t3); + EXPECT_NE(t2, t4); + EXPECT_NE(t4, t5); +} + +// --------------------------------------------------------------------------------------------------------------------- + +TEST(NmeaTest, NmeaDate) +{ + const NmeaDate d1 = { true, 2024, 10, 31 }; + EXPECT_TRUE(d1.valid); + EXPECT_EQ(d1.years, 2024); + EXPECT_EQ(d1.months, 10); + EXPECT_EQ(d1.days, 31); + const NmeaDate d1copy = { true, 2024, 10, 31 }; + const NmeaDate d2 = { true, 2024, 10, 30 }; + const NmeaDate d3 = { false, 2024, 10, 30 }; + EXPECT_EQ(d1, d1copy); + EXPECT_NE(d1, d2); + EXPECT_FALSE(d3.valid); + EXPECT_NE(d2, d3); +} + +// --------------------------------------------------------------------------------------------------------------------- + +TEST(NmeaTest, NmeaGgaPayload) +{ + { + NmeaGgaPayload gga; + const char* not_a_gga = "$GNGLL,4724.018931,N,00827.023090,E,110546.800,A,D*4F\r\n"; + EXPECT_FALSE(gga.SetFromMsg((const uint8_t*)not_a_gga, strlen(not_a_gga))); + EXPECT_EQ(gga.talker, NmeaTalkerId::UNSPECIFIED); // we should not even get the talker + } + { + NmeaGgaPayload gga; + const char* bad_gga = "$GNGGA,092207.400,4724.017956,N,00827.022383*2E\r\n"; + EXPECT_FALSE(gga.SetFromMsg((const uint8_t*)bad_gga, strlen(bad_gga))); + EXPECT_EQ(gga.talker, NmeaTalkerId::GNSS); // we should still get the talker + } + { + NmeaGgaPayload gga; + const char* good_gga = "$GNGGA,092207.400,4724.017956,N,00827.022383,E,2,41,0.43,411.542,M,47.989,M,,*79\r\n"; + EXPECT_TRUE(gga.SetFromMsg((const uint8_t*)good_gga, strlen(good_gga))); + EXPECT_EQ(gga.talker, NmeaTalkerId::GNSS); + EXPECT_TRUE(gga.time.valid); + EXPECT_EQ(gga.time.hours, 9); + EXPECT_EQ(gga.time.mins, 22); + EXPECT_NEAR(gga.time.secs, 7.4, 1e-9); + EXPECT_TRUE(gga.llh.latlon_valid); + EXPECT_TRUE(gga.llh.height_valid); + EXPECT_NEAR(gga.llh.lat, 47.0 + (24.017956 / 60.0), 1e-12); + EXPECT_NEAR(gga.llh.lon, 8.0 + (27.022383 / 60.0), 1e-12); + EXPECT_NEAR(gga.llh.height, 411.542 + 47.989, 1e-9); + EXPECT_EQ(gga.quality, NmeaQualityGga::DGNSS); + EXPECT_TRUE(gga.num_sv.valid); + EXPECT_EQ(gga.num_sv.value, 41); + EXPECT_TRUE(gga.hdop.valid); + EXPECT_NEAR(gga.hdop.value, 0.43, 1e-6); + EXPECT_FALSE(gga.diff_sta.valid); + EXPECT_EQ(gga.diff_sta.value, 0); + EXPECT_FALSE(gga.diff_age.valid); + EXPECT_EQ(gga.diff_age.value, 0.0); + } + { + NmeaGgaPayload gga; + const char* rtk_gga = + "$GNGGA,104022.800,4724.017906,N,00827.021943,E,4,43,0.46,411.424,M,47.990,M,0.8,0000*50\r\n"; + EXPECT_TRUE(gga.SetFromMsg((const uint8_t*)rtk_gga, strlen(rtk_gga))); + EXPECT_EQ(gga.talker, NmeaTalkerId::GNSS); + EXPECT_TRUE(gga.time.valid); + EXPECT_EQ(gga.time.hours, 10); + EXPECT_EQ(gga.time.mins, 40); + EXPECT_NEAR(gga.time.secs, 22.8, 1e-9); + EXPECT_TRUE(gga.llh.latlon_valid); + EXPECT_TRUE(gga.llh.height_valid); + EXPECT_NEAR(gga.llh.lat, 47.0 + (24.017906 / 60.0), 1e-12); + EXPECT_NEAR(gga.llh.lon, 8.0 + (27.021943 / 60.0), 1e-12); + EXPECT_NEAR(gga.llh.height, 411.424 + 47.990, 1e-9); + EXPECT_EQ(gga.quality, NmeaQualityGga::RTK_FIXED); + EXPECT_TRUE(gga.num_sv.valid); + EXPECT_EQ(gga.num_sv.value, 43); + EXPECT_TRUE(gga.hdop.valid); + EXPECT_NEAR(gga.hdop.value, 0.46, 1e-6); + EXPECT_TRUE(gga.diff_sta.valid); + EXPECT_EQ(gga.diff_sta.value, 0); + EXPECT_TRUE(gga.diff_age.valid); + EXPECT_NEAR(gga.diff_age.value, 0.8, 1e-6); + } + { + NmeaGgaPayload gga; + const char* good_gga = "$GNGGA,235943.812,,,,,0,00,99.99,,M,,M,,*49\r\n"; + EXPECT_TRUE(gga.SetFromMsg((const uint8_t*)good_gga, strlen(good_gga))); + EXPECT_EQ(gga.talker, NmeaTalkerId::GNSS); + EXPECT_TRUE(gga.time.valid); + EXPECT_EQ(gga.time.hours, 23); + EXPECT_EQ(gga.time.mins, 59); + EXPECT_NEAR(gga.time.secs, 43.812, 1e-9); + EXPECT_FALSE(gga.llh.latlon_valid); + EXPECT_EQ(gga.llh.lat, 0.0); + EXPECT_EQ(gga.llh.lon, 0.0); + EXPECT_FALSE(gga.llh.height_valid); + EXPECT_EQ(gga.llh.height, 0.0); + EXPECT_EQ(gga.quality, NmeaQualityGga::NOFIX); + EXPECT_TRUE(gga.num_sv.valid); + EXPECT_EQ(gga.num_sv.value, 0); + EXPECT_FALSE(gga.hdop.valid); + EXPECT_EQ(gga.hdop.value, 0.0); + EXPECT_FALSE(gga.diff_sta.valid); + EXPECT_EQ(gga.diff_sta.value, 0); + EXPECT_FALSE(gga.diff_age.valid); + EXPECT_EQ(gga.diff_age.value, 0.0); + } +} + +// --------------------------------------------------------------------------------------------------------------------- + +TEST(NmeaTest, NmeaGllPayload) +{ + { + NmeaGllPayload gll; + const char* good_gll = "$GNGLL,4724.018931,N,00827.023090,E,110546.800,A,D*4F\r\n"; + EXPECT_TRUE(gll.SetFromMsg((const uint8_t*)good_gll, strlen(good_gll))); + EXPECT_EQ(gll.talker, NmeaTalkerId::GNSS); + EXPECT_TRUE(gll.time.valid); + EXPECT_EQ(gll.time.hours, 11); + EXPECT_EQ(gll.time.mins, 5); + EXPECT_NEAR(gll.time.secs, 46.8, 1e-9); + EXPECT_TRUE(gll.llh.latlon_valid); + EXPECT_NEAR(gll.llh.lat, 47.0 + (24.018931 / 60.0), 1e-12); + EXPECT_NEAR(gll.llh.lon, 8.0 + (27.023090 / 60.0), 1e-12); + EXPECT_FALSE(gll.llh.height_valid); + EXPECT_NEAR(gll.llh.height, 0.0, 1e-9); + EXPECT_EQ(gll.status, NmeaStatusGllRmc::VALID); + EXPECT_EQ(gll.mode, NmeaModeGllVtg::DGNSS); + } + { + NmeaGllPayload gll; + const char* gll_coldstart = "$GNGLL,,,,,235943.612,V,N*6B\r\n"; + EXPECT_TRUE(gll.SetFromMsg((const uint8_t*)gll_coldstart, strlen(gll_coldstart))); + EXPECT_EQ(gll.talker, NmeaTalkerId::GNSS); + EXPECT_TRUE(gll.time.valid); + EXPECT_EQ(gll.time.hours, 23); + EXPECT_EQ(gll.time.mins, 59); + EXPECT_NEAR(gll.time.secs, 43.612, 1e-9); + EXPECT_FALSE(gll.llh.latlon_valid); + EXPECT_EQ(gll.llh.lat, 0.0); + EXPECT_EQ(gll.llh.lon, 0.0); + EXPECT_FALSE(gll.llh.height_valid); + EXPECT_EQ(gll.llh.height, 0.0); + EXPECT_EQ(gll.status, NmeaStatusGllRmc::INVALID); + EXPECT_EQ(gll.mode, NmeaModeGllVtg::INVALID); + } +} + +// --------------------------------------------------------------------------------------------------------------------- + +TEST(NmeaTest, NmeaRmcPayload) +{ + { + NmeaRmcPayload rmc; + const char* good_rmc = "$GNRMC,110546.800,A,4724.018931,N,00827.023090,E,0.015,139.17,231024,,,D,V*3D\r\n"; + EXPECT_TRUE(rmc.SetFromMsg((const uint8_t*)good_rmc, strlen(good_rmc))); + EXPECT_EQ(rmc.talker, NmeaTalkerId::GNSS); + EXPECT_TRUE(rmc.time.valid); + EXPECT_EQ(rmc.time.hours, 11); + EXPECT_EQ(rmc.time.mins, 5); + EXPECT_NEAR(rmc.time.secs, 46.8, 1e-9); + EXPECT_EQ(rmc.status, NmeaStatusGllRmc::VALID); + EXPECT_TRUE(rmc.llh.latlon_valid); + EXPECT_NEAR(rmc.llh.lat, 47.0 + (24.018931 / 60.0), 1e-12); + EXPECT_NEAR(rmc.llh.lon, 8.0 + (27.023090 / 60.0), 1e-12); + EXPECT_FALSE(rmc.llh.height_valid); // no height in RMC + EXPECT_NEAR(rmc.llh.height, 0.0, 1e-9); + EXPECT_TRUE(rmc.speed.valid); + EXPECT_NEAR(rmc.speed.value, 0.015, 1e-6); + EXPECT_TRUE(rmc.course.valid); + EXPECT_NEAR(rmc.course.value, 139.17, 1e-3); + EXPECT_TRUE(rmc.date.valid); + EXPECT_EQ(rmc.date.years, 2024); + EXPECT_EQ(rmc.date.months, 10); + EXPECT_EQ(rmc.date.days, 23); + EXPECT_EQ(rmc.mode, NmeaModeRmcGns::DGNSS); + EXPECT_EQ(rmc.navstatus, NmeaNavStatusRmc::NA); + } + { + NmeaRmcPayload rmc; + const char* rmc_coldstart = "$GNRMC,235943.412,V,,,,,,,050180,,,N,V*28\r\n"; + EXPECT_TRUE(rmc.SetFromMsg((const uint8_t*)rmc_coldstart, strlen(rmc_coldstart))); + EXPECT_EQ(rmc.talker, NmeaTalkerId::GNSS); + EXPECT_TRUE(rmc.time.valid); + EXPECT_EQ(rmc.time.hours, 23); + EXPECT_EQ(rmc.time.mins, 59); + EXPECT_NEAR(rmc.time.secs, 43.412, 1e-9); + EXPECT_EQ(rmc.status, NmeaStatusGllRmc::INVALID); + EXPECT_FALSE(rmc.llh.latlon_valid); + EXPECT_EQ(rmc.llh.lat, 0.0); + EXPECT_EQ(rmc.llh.lon, 0.0); + EXPECT_FALSE(rmc.llh.height_valid); + EXPECT_EQ(rmc.llh.height, 0.0); + EXPECT_FALSE(rmc.speed.valid); + EXPECT_EQ(rmc.speed.value, 0.0); + EXPECT_FALSE(rmc.course.valid); + EXPECT_EQ(rmc.course.value, 0.0); + EXPECT_FALSE(rmc.date.valid); + EXPECT_EQ(rmc.date.years, 1980); + EXPECT_EQ(rmc.date.months, 1); + EXPECT_EQ(rmc.date.days, 5); + EXPECT_EQ(rmc.mode, NmeaModeRmcGns::INVALID); + EXPECT_EQ(rmc.navstatus, NmeaNavStatusRmc::NA); + } +} + +// --------------------------------------------------------------------------------------------------------------------- + +TEST(NmeaTest, NmeaVtgPayload) +{ + { + NmeaVtgPayload vtg; + const char* good_vtg = "$GNVTG,139.17,T,,M,0.015,N,0.027,K,D*2A\r\n"; + EXPECT_TRUE(vtg.SetFromMsg((const uint8_t*)good_vtg, strlen(good_vtg))); + EXPECT_EQ(vtg.talker, NmeaTalkerId::GNSS); + EXPECT_TRUE(vtg.cogt.valid); + EXPECT_NEAR(vtg.cogt.value, 139.17, 1e-4); + EXPECT_TRUE(vtg.sogn.valid); + EXPECT_NEAR(vtg.sogn.value, 0.015, 1e-6); + EXPECT_TRUE(vtg.sogk.valid); + EXPECT_NEAR(vtg.sogk.value, 0.027, 1e-6); + } + { + NmeaVtgPayload vtg; + const char* vtg_coldstart = "$GNVTG,,T,,M,,N,,K,N*32\r\n"; + EXPECT_TRUE(vtg.SetFromMsg((const uint8_t*)vtg_coldstart, strlen(vtg_coldstart))); + EXPECT_EQ(vtg.talker, NmeaTalkerId::GNSS); + EXPECT_FALSE(vtg.cogt.valid); + EXPECT_EQ(vtg.cogt.value, 0.0); + EXPECT_FALSE(vtg.sogn.valid); + EXPECT_EQ(vtg.sogn.value, 0.0); + EXPECT_FALSE(vtg.sogk.valid); + EXPECT_EQ(vtg.sogk.value, 0.0); + } +} + +// --------------------------------------------------------------------------------------------------------------------- + +TEST(NmeaTest, NmeaGsaPayload) +{ + { + NmeaGsaPayload gsa; + const char* good_gsa = "$GNGSA,A,3,03,04,06,07,09,11,19,20,26,30,31,,0.79,0.46,0.64,1*0F\r\n"; + EXPECT_TRUE(gsa.SetFromMsg((const uint8_t*)good_gsa, strlen(good_gsa))); + EXPECT_EQ(gsa.talker, NmeaTalkerId::GNSS); + EXPECT_EQ(gsa.opmode, NmeaOpModeGsa::AUTO); + EXPECT_EQ(gsa.navmode, NmeaNavModeGsa::FIX3D); + EXPECT_EQ(gsa.num_sats, 11); + EXPECT_TRUE(gsa.sats[0].valid); + EXPECT_EQ(gsa.sats[0].system, NmeaSystemId::GPS_SBAS); + EXPECT_EQ(gsa.sats[0].svid, 3); + EXPECT_TRUE(gsa.sats[1].valid); + EXPECT_EQ(gsa.sats[1].system, NmeaSystemId::GPS_SBAS); + EXPECT_EQ(gsa.sats[1].svid, 4); + EXPECT_TRUE(gsa.sats[2].valid); + EXPECT_EQ(gsa.sats[2].system, NmeaSystemId::GPS_SBAS); + EXPECT_EQ(gsa.sats[2].svid, 6); + EXPECT_TRUE(gsa.sats[3].valid); + EXPECT_EQ(gsa.sats[3].system, NmeaSystemId::GPS_SBAS); + EXPECT_EQ(gsa.sats[3].svid, 7); + EXPECT_TRUE(gsa.sats[4].valid); + EXPECT_EQ(gsa.sats[4].system, NmeaSystemId::GPS_SBAS); + EXPECT_EQ(gsa.sats[4].svid, 9); + EXPECT_TRUE(gsa.sats[5].valid); + EXPECT_EQ(gsa.sats[5].system, NmeaSystemId::GPS_SBAS); + EXPECT_EQ(gsa.sats[5].svid, 11); + EXPECT_TRUE(gsa.sats[6].valid); + EXPECT_EQ(gsa.sats[6].system, NmeaSystemId::GPS_SBAS); + EXPECT_EQ(gsa.sats[6].svid, 19); + EXPECT_TRUE(gsa.sats[7].valid); + EXPECT_EQ(gsa.sats[7].system, NmeaSystemId::GPS_SBAS); + EXPECT_EQ(gsa.sats[7].svid, 20); + EXPECT_TRUE(gsa.sats[8].valid); + EXPECT_EQ(gsa.sats[8].system, NmeaSystemId::GPS_SBAS); + EXPECT_EQ(gsa.sats[8].svid, 26); + EXPECT_TRUE(gsa.sats[9].valid); + EXPECT_EQ(gsa.sats[9].system, NmeaSystemId::GPS_SBAS); + EXPECT_EQ(gsa.sats[9].svid, 30); + EXPECT_TRUE(gsa.sats[10].valid); + EXPECT_EQ(gsa.sats[10].system, NmeaSystemId::GPS_SBAS); + EXPECT_EQ(gsa.sats[10].svid, 31); + EXPECT_FALSE(gsa.sats[11].valid); + EXPECT_EQ(gsa.sats[11].system, NmeaSystemId::UNSPECIFIED); + EXPECT_EQ(gsa.sats[11].svid, 0); + EXPECT_TRUE(gsa.pdop.valid); + EXPECT_NEAR(gsa.pdop.value, 0.79, 1e-4); + EXPECT_TRUE(gsa.hdop.valid); + EXPECT_NEAR(gsa.hdop.value, 0.46, 1e-4); + EXPECT_TRUE(gsa.vdop.valid); + EXPECT_NEAR(gsa.vdop.value, 0.64, 1e-4); + EXPECT_EQ(gsa.system, NmeaSystemId::GPS_SBAS); + } + { + NmeaGsaPayload gsa; + const char* gsa_coldstart = "$GNGSA,A,1,,,,,,,,,,,,,99.99,99.99,99.99,5*37\r\n"; + EXPECT_TRUE(gsa.SetFromMsg((const uint8_t*)gsa_coldstart, strlen(gsa_coldstart))); + EXPECT_EQ(gsa.talker, NmeaTalkerId::GNSS); + EXPECT_EQ(gsa.opmode, NmeaOpModeGsa::AUTO); + EXPECT_EQ(gsa.navmode, NmeaNavModeGsa::NOFIX); + EXPECT_EQ(gsa.num_sats, 0); + EXPECT_FALSE(gsa.sats[0].valid); + EXPECT_EQ(gsa.sats[0].system, NmeaSystemId::UNSPECIFIED); + EXPECT_EQ(gsa.sats[0].svid, 0); + EXPECT_FALSE(gsa.sats[1].valid); + EXPECT_EQ(gsa.sats[1].system, NmeaSystemId::UNSPECIFIED); + EXPECT_EQ(gsa.sats[1].svid, 0); + EXPECT_FALSE(gsa.sats[2].valid); + EXPECT_EQ(gsa.sats[2].system, NmeaSystemId::UNSPECIFIED); + EXPECT_EQ(gsa.sats[2].svid, 0); + EXPECT_FALSE(gsa.sats[3].valid); + EXPECT_EQ(gsa.sats[3].system, NmeaSystemId::UNSPECIFIED); + EXPECT_EQ(gsa.sats[3].svid, 0); + EXPECT_FALSE(gsa.sats[4].valid); + EXPECT_EQ(gsa.sats[4].system, NmeaSystemId::UNSPECIFIED); + EXPECT_EQ(gsa.sats[4].svid, 0); + EXPECT_FALSE(gsa.sats[5].valid); + EXPECT_EQ(gsa.sats[5].system, NmeaSystemId::UNSPECIFIED); + EXPECT_EQ(gsa.sats[5].svid, 0); + EXPECT_FALSE(gsa.sats[6].valid); + EXPECT_EQ(gsa.sats[6].system, NmeaSystemId::UNSPECIFIED); + EXPECT_EQ(gsa.sats[6].svid, 0); + EXPECT_FALSE(gsa.sats[7].valid); + EXPECT_EQ(gsa.sats[7].system, NmeaSystemId::UNSPECIFIED); + EXPECT_EQ(gsa.sats[7].svid, 0); + EXPECT_FALSE(gsa.sats[8].valid); + EXPECT_EQ(gsa.sats[8].system, NmeaSystemId::UNSPECIFIED); + EXPECT_EQ(gsa.sats[8].svid, 0); + EXPECT_FALSE(gsa.sats[9].valid); + EXPECT_EQ(gsa.sats[9].system, NmeaSystemId::UNSPECIFIED); + EXPECT_EQ(gsa.sats[9].svid, 0); + EXPECT_FALSE(gsa.sats[10].valid); + EXPECT_EQ(gsa.sats[10].system, NmeaSystemId::UNSPECIFIED); + EXPECT_EQ(gsa.sats[10].svid, 0); + EXPECT_FALSE(gsa.sats[11].valid); + EXPECT_EQ(gsa.sats[11].system, NmeaSystemId::UNSPECIFIED); + EXPECT_EQ(gsa.sats[11].svid, 0); + EXPECT_FALSE(gsa.pdop.valid); + EXPECT_EQ(gsa.pdop.value, 0.0); + EXPECT_FALSE(gsa.hdop.valid); + EXPECT_EQ(gsa.hdop.value, 0.0); + EXPECT_FALSE(gsa.vdop.valid); + EXPECT_EQ(gsa.vdop.value, 0.0); + EXPECT_EQ(gsa.system, NmeaSystemId::QZSS); + } +} + +// --------------------------------------------------------------------------------------------------------------------- + +TEST(NmeaTest, NmeaGsvPayload) +{ + { + NmeaGsvPayload gsv; + const char* gsv_2_of_4 = // clang-format off + "$GPGSV,4,2,14," "09,84,270,52," "11,,,46," "16,03,080,," "17,03,218,35," "1*XX\r\n"; // clang-format on + EXPECT_TRUE(gsv.SetFromMsg((const uint8_t*)gsv_2_of_4, strlen(gsv_2_of_4))); + EXPECT_EQ(gsv.talker, NmeaTalkerId::GPS_SBAS); + EXPECT_TRUE(gsv.num_msgs.valid); + EXPECT_EQ(gsv.num_msgs.value, 4); + EXPECT_TRUE(gsv.msg_num.valid); + EXPECT_EQ(gsv.msg_num.value, 2); + EXPECT_TRUE(gsv.tot_num_sat.valid); + EXPECT_EQ(gsv.tot_num_sat.value, 14); + EXPECT_TRUE(gsv.azels[0].valid); + EXPECT_EQ(gsv.num_azels, 3); + EXPECT_EQ(gsv.azels[0].system, NmeaSystemId::GPS_SBAS); + EXPECT_EQ(gsv.azels[0].svid, 9); + EXPECT_EQ(gsv.azels[0].el, 84); + EXPECT_EQ(gsv.azels[0].az, 270); + EXPECT_TRUE(gsv.azels[1].valid); + EXPECT_EQ(gsv.azels[1].system, NmeaSystemId::GPS_SBAS); + EXPECT_EQ(gsv.azels[1].svid, 16); + EXPECT_EQ(gsv.azels[1].el, 3); + EXPECT_EQ(gsv.azels[1].az, 80); + EXPECT_TRUE(gsv.azels[2].valid); + EXPECT_EQ(gsv.azels[2].system, NmeaSystemId::GPS_SBAS); + EXPECT_EQ(gsv.azels[2].svid, 17); + EXPECT_EQ(gsv.azels[2].el, 3); + EXPECT_EQ(gsv.azels[2].az, 218); + EXPECT_FALSE(gsv.azels[3].valid); + EXPECT_EQ(gsv.azels[3].system, NmeaSystemId::UNSPECIFIED); + EXPECT_EQ(gsv.azels[3].svid, 0); + EXPECT_EQ(gsv.azels[3].el, 0); + EXPECT_EQ(gsv.azels[3].az, 0); + EXPECT_EQ(gsv.num_cnos, 3); + EXPECT_TRUE(gsv.cnos[0].valid); + EXPECT_EQ(gsv.cnos[0].system, NmeaSystemId::GPS_SBAS); + EXPECT_EQ(gsv.cnos[0].svid, 9); + EXPECT_EQ(gsv.cnos[0].signal, NmeaSignalId::GPS_L1CA); + EXPECT_EQ(gsv.cnos[0].cno, 52); + EXPECT_TRUE(gsv.cnos[1].valid); + EXPECT_EQ(gsv.cnos[1].system, NmeaSystemId::GPS_SBAS); + EXPECT_EQ(gsv.cnos[1].svid, 11); + EXPECT_EQ(gsv.cnos[1].signal, NmeaSignalId::GPS_L1CA); + EXPECT_EQ(gsv.cnos[1].cno, 46); + EXPECT_TRUE(gsv.cnos[2].valid); + EXPECT_EQ(gsv.cnos[2].system, NmeaSystemId::GPS_SBAS); + EXPECT_EQ(gsv.cnos[2].svid, 17); + EXPECT_EQ(gsv.cnos[2].signal, NmeaSignalId::GPS_L1CA); + EXPECT_EQ(gsv.cnos[2].cno, 35); + EXPECT_FALSE(gsv.cnos[3].valid); + EXPECT_EQ(gsv.cnos[3].system, NmeaSystemId::UNSPECIFIED); + EXPECT_EQ(gsv.cnos[3].svid, 0); + EXPECT_EQ(gsv.cnos[3].signal, NmeaSignalId::UNSPECIFIED); + EXPECT_EQ(gsv.cnos[3].cno, 0); + EXPECT_EQ(gsv.system, NmeaSystemId::GPS_SBAS); + EXPECT_EQ(gsv.signal, NmeaSignalId::GPS_L1CA); + } + { + NmeaGsvPayload gsv; + const char* gsv_4_of_4 = "$GPGSV,4,4,14,31,08,034,46,36,31,149,43,1*62\r\n"; + EXPECT_TRUE(gsv.SetFromMsg((const uint8_t*)gsv_4_of_4, strlen(gsv_4_of_4))); + EXPECT_EQ(gsv.talker, NmeaTalkerId::GPS_SBAS); + EXPECT_TRUE(gsv.num_msgs.valid); + EXPECT_EQ(gsv.num_msgs.value, 4); + EXPECT_TRUE(gsv.msg_num.valid); + EXPECT_EQ(gsv.msg_num.value, 4); + EXPECT_TRUE(gsv.tot_num_sat.valid); + EXPECT_EQ(gsv.tot_num_sat.value, 14); + EXPECT_EQ(gsv.num_azels, 2); + EXPECT_TRUE(gsv.azels[0].valid); + EXPECT_EQ(gsv.azels[0].system, NmeaSystemId::GPS_SBAS); + EXPECT_EQ(gsv.azels[0].svid, 31); + EXPECT_EQ(gsv.azels[0].el, 8); + EXPECT_EQ(gsv.azels[0].az, 34); + EXPECT_TRUE(gsv.azels[1].valid); + EXPECT_EQ(gsv.azels[1].system, NmeaSystemId::GPS_SBAS); + EXPECT_EQ(gsv.azels[1].svid, 36); + EXPECT_EQ(gsv.azels[1].el, 31); + EXPECT_EQ(gsv.azels[1].az, 149); + EXPECT_FALSE(gsv.azels[2].valid); + EXPECT_EQ(gsv.azels[2].system, NmeaSystemId::UNSPECIFIED); + EXPECT_EQ(gsv.azels[2].svid, 0); + EXPECT_EQ(gsv.azels[2].el, 0); + EXPECT_EQ(gsv.azels[2].az, 0); + EXPECT_FALSE(gsv.azels[3].valid); + EXPECT_EQ(gsv.azels[3].system, NmeaSystemId::UNSPECIFIED); + EXPECT_EQ(gsv.azels[3].svid, 0); + EXPECT_EQ(gsv.azels[3].el, 0); + EXPECT_EQ(gsv.azels[3].az, 0); + EXPECT_EQ(gsv.num_cnos, 2); + EXPECT_TRUE(gsv.cnos[0].valid); + EXPECT_EQ(gsv.cnos[0].system, NmeaSystemId::GPS_SBAS); + EXPECT_EQ(gsv.cnos[0].svid, 31); + EXPECT_EQ(gsv.cnos[0].signal, NmeaSignalId::GPS_L1CA); + EXPECT_EQ(gsv.cnos[0].cno, 46); + EXPECT_TRUE(gsv.cnos[1].valid); + EXPECT_EQ(gsv.cnos[1].system, NmeaSystemId::GPS_SBAS); + EXPECT_EQ(gsv.cnos[1].svid, 36); + EXPECT_EQ(gsv.cnos[1].signal, NmeaSignalId::GPS_L1CA); + EXPECT_EQ(gsv.cnos[1].cno, 43); + EXPECT_FALSE(gsv.cnos[2].valid); + EXPECT_EQ(gsv.cnos[2].system, NmeaSystemId::UNSPECIFIED); + EXPECT_EQ(gsv.cnos[2].svid, 0); + EXPECT_EQ(gsv.cnos[2].signal, NmeaSignalId::UNSPECIFIED); + EXPECT_EQ(gsv.cnos[2].cno, 0); + EXPECT_FALSE(gsv.cnos[3].valid); + EXPECT_EQ(gsv.cnos[3].system, NmeaSystemId::UNSPECIFIED); + EXPECT_EQ(gsv.cnos[3].svid, 0); + EXPECT_EQ(gsv.cnos[3].signal, NmeaSignalId::UNSPECIFIED); + EXPECT_EQ(gsv.cnos[3].cno, 0); + } + { + NmeaGsvPayload gsv; + const char* gsv_1_of_1_nosv = "$GAGSV,1,1,00,1*75\r\n"; + EXPECT_TRUE(gsv.SetFromMsg((const uint8_t*)gsv_1_of_1_nosv, strlen(gsv_1_of_1_nosv))); + EXPECT_EQ(gsv.talker, NmeaTalkerId::GAL); + EXPECT_TRUE(gsv.num_msgs.valid); + EXPECT_EQ(gsv.num_msgs.value, 1); + EXPECT_TRUE(gsv.msg_num.valid); + EXPECT_EQ(gsv.msg_num.value, 1); + EXPECT_TRUE(gsv.tot_num_sat.valid); + EXPECT_EQ(gsv.tot_num_sat.value, 0); + EXPECT_EQ(gsv.num_azels, 0); + EXPECT_EQ(gsv.num_cnos, 0); + for (int ix = 0; ix < 4; ix++) { + EXPECT_FALSE(gsv.azels[0].valid); + EXPECT_EQ(gsv.azels[ix].system, NmeaSystemId::UNSPECIFIED); + EXPECT_EQ(gsv.azels[ix].svid, 0); + EXPECT_EQ(gsv.azels[ix].el, 0); + EXPECT_EQ(gsv.azels[ix].az, 0); + EXPECT_EQ(gsv.cnos[ix].system, NmeaSystemId::UNSPECIFIED); + EXPECT_EQ(gsv.cnos[ix].svid, 0); + EXPECT_EQ(gsv.cnos[ix].signal, NmeaSignalId::UNSPECIFIED); + EXPECT_EQ(gsv.cnos[ix].cno, 0); + } + } + { + NmeaGsvPayload gsv; + const char* bad_gsv_too_many_sv = "$GLGSV,1,1,12,1*75\r\n"; + EXPECT_FALSE(gsv.SetFromMsg((const uint8_t*)bad_gsv_too_many_sv, strlen(bad_gsv_too_many_sv))); + EXPECT_EQ(gsv.talker, NmeaTalkerId::GLO); + EXPECT_TRUE(gsv.num_msgs.valid); + EXPECT_EQ(gsv.num_msgs.value, 1); + EXPECT_TRUE(gsv.msg_num.valid); + EXPECT_EQ(gsv.msg_num.value, 1); + EXPECT_TRUE(gsv.tot_num_sat.valid); + EXPECT_EQ(gsv.tot_num_sat.value, 12); + EXPECT_EQ(gsv.num_azels, 0); + EXPECT_EQ(gsv.num_cnos, 0); + for (int ix = 0; ix < 4; ix++) { + EXPECT_FALSE(gsv.azels[0].valid); + EXPECT_EQ(gsv.azels[ix].system, NmeaSystemId::UNSPECIFIED); + EXPECT_EQ(gsv.azels[ix].svid, 0); + EXPECT_EQ(gsv.azels[ix].el, 0); + EXPECT_EQ(gsv.azels[ix].az, 0); + EXPECT_EQ(gsv.cnos[ix].system, NmeaSystemId::UNSPECIFIED); + EXPECT_EQ(gsv.cnos[ix].svid, 0); + EXPECT_EQ(gsv.cnos[ix].signal, NmeaSignalId::UNSPECIFIED); + EXPECT_EQ(gsv.cnos[ix].cno, 0); + } + } +} + +// --------------------------------------------------------------------------------------------------------------------- + +TEST(NmeaTest, NmeaCollectGsaGsv) +{ + const char* gsa_msgs[] = { + // clang-format off + "$GNGSA,A,3," "03,04,06,07,09,11,19,20,26,30,31,," "0.79,0.46,0.64,1*XX\r\n", + "$GNGSA,A,3," "69,71,78,79,80,84,85,86,,,,," "0.79,0.46,0.64,2*XX\r\n", + "$GNGSA,A,3," "02,07,08,12,19,26,29,33,,,,," "0.79,0.46,0.64,3*XX\r\n", // (2) + "$GNGSA,A,3," "06,09,11,12,14,16,21,22,26,28,33,34," "0.79,0.46,0.64,4*XX\r\n", + "$GNGSA,A,3," ",,,,,,,,,,,," "0.79,0.46,0.64,5*XX\r\n", + }; // clang-format on + const char* gsv_msgs[] = { + // clang-format off + "$GPGSV,4,1,14," "03,30,103,46," "04,59,056,48," "06,62,267,50," "07,31,170,46," "1*XX\r\n", // (1) + "$GPGSV,4,2,14," "09,84,270,52," "11,28,311,46," "16,03,080,42," "17,03,218,35," "1*XX\r\n", + "$GPGSV,4,3,14," "19,14,239,42," "20,12,44,," "26,07,049,43," "30,05,191,36," "1*XX\r\n", + "$GPGSV,4,4,14," "31,,,46," "36,31,149,," "1*XX\r\n", + "$GPGSV,2,1,07," "03,30,103,48," "04,59,056,52," "06,62,267,52," "09,84,270,52," "8*XX\r\n", + "$GPGSV,2,2,07," "11,28,311,49," "26,07,049,48," "30,,,39," "8*XX\r\n", + "$GLGSV,2,1,08," "69,36,055,52," "71,17,265,45," "78,14,023,45," "79,28,076,49," "1*XX\r\n", + "$GLGSV,2,2,08," "80,12,129,45," "84,18,188,33," "85,53,243,52," "86,32,321,50," "1*XX\r\n", + "$GAGSV,3,1,09," "02,06,041,41," "07,56,057,47," "08,05,057,40," "12,16,320,37," "7*XX\r\n", + "$GAGSV,3,2,09," "19,19,237,37," "26,47,176,45," "29,64,237,49," "30,03,089,37," "7*XX\r\n", // (2) + "$GAGSV,3,3,09," "33,63,276,," "7*XX\r\n", + "$GAGSV,3,1,09," "02,06,041,43," "07,56,057,50," "08,05,057,43," "12,16,320,39," "1*XX\r\n", + "$GAGSV,3,2,09," "19,19,237,37," "26,47,176,49," "29,64,237,," "30,03,089,41," "1*XX\r\n", + "$GAGSV,3,3,09," "33,63,276,51," "1*XX\r\n", + "$GBGSV,5,1,17," "06,23,042,42," "09,33,050,43," "11,37,231,46," "12,06,186,37," "1*XX\r\n", + "$GBGSV,5,2,17," "14,35,274,45," "16,16,037,40," "21,57,066,50," "22,08,082,43," "1*XX\r\n", + "$GBGSV,5,3,17," "26,18,144,42," "28,13,324,44," "33,10,269,45," "34,21,208,44," "1*XX\r\n", + "$GBGSV,5,4,17," "36,12,036,43," "39,10,035,," "42,62,288,50," "43,36,260,48," "1*XX\r\n", + "$GBGSV,5,5,17," "45,30,085,47," "1*XX\r\n", + "$GBGSV,3,1,11," "21,57,066,51," "22,08,082,45," "26,18,144,44," "28,13,324,46," "5*XX\r\n", + "$GBGSV,3,2,11," "33,10,269,45," "34,21,208,43," "36,12,036,46," "39,10,035,44," "5*XX\r\n", + "$GBGSV,3,3,11," "42,62,288,52," "43,36,260,," "45,30,085,," "5*XX\r\n", + "$GQGSV,1,1,00," "1*XX\r\n", + "$GQGSV,1,1,00," "8*XX\r\n", + }; // clang-format on + { + NmeaCollectGsaGsv coll; + for (auto& gsa_msg : gsa_msgs) { + NmeaGsaPayload gsa; + // fprintf(stderr, "GSA: %s", gsa_msg); + EXPECT_TRUE(gsa.SetFromMsg((const uint8_t*)gsa_msg, strlen(gsa_msg))); + EXPECT_TRUE(coll.AddGsa(gsa)); + } + for (auto& gsv_msg : gsv_msgs) { + NmeaGsvPayload gsv; + // fprintf(stderr, "GSV: %s", gsv_msg); + EXPECT_TRUE(gsv.SetFromMsg((const uint8_t*)gsv_msg, strlen(gsv_msg))); + EXPECT_TRUE(coll.AddGsv(gsv)); + } + coll.Complete(); + // A few checks... + EXPECT_EQ(coll.sats_.size(), 47); + EXPECT_EQ(coll.sigs_.size(), 68); + // (1) 03,30,103,46 + EXPECT_EQ(coll.sats_[0].system_, NmeaSystemId::GPS_SBAS); + EXPECT_EQ(coll.sats_[0].svid_, 3); + EXPECT_EQ(coll.sats_[0].az_, 103); + EXPECT_EQ(coll.sats_[0].el_, 30); + EXPECT_EQ(coll.sigs_[0].system_, NmeaSystemId::GPS_SBAS); + EXPECT_EQ(coll.sigs_[0].svid_, 3); + EXPECT_EQ(coll.sigs_[0].cno_, 46); + EXPECT_TRUE(coll.sigs_[0].used_); + // (2) 26,47,176,45 (used, in GSA) and 30,03,089,37 (not used, not in GSA) + EXPECT_EQ(coll.sats_[26].system_, NmeaSystemId::GAL); + EXPECT_EQ(coll.sats_[26].svid_, 26); + EXPECT_EQ(coll.sats_[26].az_, 176); + EXPECT_EQ(coll.sats_[26].el_, 47); + EXPECT_EQ(coll.sigs_[40].system_, NmeaSystemId::GAL); + EXPECT_EQ(coll.sigs_[40].svid_, 26); + EXPECT_EQ(coll.sigs_[40].cno_, 45); + EXPECT_TRUE(coll.sigs_[40].used_); // used + EXPECT_EQ(coll.sats_[28].system_, NmeaSystemId::GAL); + EXPECT_EQ(coll.sats_[28].svid_, 30); + EXPECT_EQ(coll.sats_[28].az_, 89); + EXPECT_EQ(coll.sats_[28].el_, 3); + EXPECT_EQ(coll.sigs_[42].system_, NmeaSystemId::GAL); + EXPECT_EQ(coll.sigs_[42].svid_, 30); + EXPECT_EQ(coll.sigs_[42].cno_, 37); + EXPECT_FALSE(coll.sigs_[42].used_); // not used + } + { + NmeaCollectGsaGsv coll; + std::vector gsas; + std::vector gsvs; + for (auto& gsa_msg : gsa_msgs) { + NmeaGsaPayload gsa; + EXPECT_TRUE(gsa.SetFromMsg((const uint8_t*)gsa_msg, strlen(gsa_msg))); + gsas.push_back(gsa); + } + for (auto& gsv_msg : gsv_msgs) { + NmeaGsvPayload gsv; + EXPECT_TRUE(gsv.SetFromMsg((const uint8_t*)gsv_msg, strlen(gsv_msg))); + gsvs.push_back(gsv); + } + EXPECT_TRUE(coll.AddGsaAndGsv(gsas, gsvs)); + + // A few checks... + EXPECT_EQ(coll.sats_.size(), 47); + EXPECT_EQ(coll.sigs_.size(), 68); + // (1) 03,30,103,46 + EXPECT_EQ(coll.sats_[0].system_, NmeaSystemId::GPS_SBAS); + EXPECT_EQ(coll.sats_[0].svid_, 3); + EXPECT_EQ(coll.sats_[0].az_, 103); + EXPECT_EQ(coll.sats_[0].el_, 30); + EXPECT_EQ(coll.sigs_[0].system_, NmeaSystemId::GPS_SBAS); + EXPECT_EQ(coll.sigs_[0].svid_, 3); + EXPECT_EQ(coll.sigs_[0].cno_, 46); + EXPECT_TRUE(coll.sigs_[0].used_); + // (2) 26,47,176,45 (used, in GSA) and 30,03,089,37 (not used, not in GSA) + EXPECT_EQ(coll.sats_[26].system_, NmeaSystemId::GAL); + EXPECT_EQ(coll.sats_[26].svid_, 26); + EXPECT_EQ(coll.sats_[26].az_, 176); + EXPECT_EQ(coll.sats_[26].el_, 47); + EXPECT_EQ(coll.sigs_[40].system_, NmeaSystemId::GAL); + EXPECT_EQ(coll.sigs_[40].svid_, 26); + EXPECT_EQ(coll.sigs_[40].cno_, 45); + EXPECT_TRUE(coll.sigs_[40].used_); // used + EXPECT_EQ(coll.sats_[28].system_, NmeaSystemId::GAL); + EXPECT_EQ(coll.sats_[28].svid_, 30); + EXPECT_EQ(coll.sats_[28].az_, 89); + EXPECT_EQ(coll.sats_[28].el_, 3); + EXPECT_EQ(coll.sigs_[42].system_, NmeaSystemId::GAL); + EXPECT_EQ(coll.sigs_[42].svid_, 30); + EXPECT_EQ(coll.sigs_[42].cno_, 37); + EXPECT_FALSE(coll.sigs_[42].used_); // not used + } +} + +/* ****************************************************************************************************************** */ +} // namespace + +int main(int argc, char** argv) +{ + testing::InitGoogleTest(&argc, argv); + auto level = fpsdk::common::logging::LoggingLevel::WARNING; + for (int ix = 0; ix < argc; ix++) { + if ((argv[ix][0] == '-') && argv[ix][1] == 'v') { + level++; + } + } + fpsdk::common::logging::LoggingSetParams(level); + return RUN_ALL_TESTS(); +} diff --git a/fpsdk_common/test/parser_novb_test.cpp b/fpsdk_common/test/parser_novb_test.cpp new file mode 100644 index 0000000..3c09017 --- /dev/null +++ b/fpsdk_common/test/parser_novb_test.cpp @@ -0,0 +1,140 @@ +/** + * \verbatim + * ___ ___ + * \ \ / / + * \ \/ / Copyright (c) Fixposition AG (www.fixposition.com) and contributors + * / /\ \ License: see the LICENSE file + * /__/ \__\ + * \endverbatim + * + * @file + * @brief Fixposition SDK: tests for fpsdk::common::parser::novb + */ + +/* LIBC/STL */ +#include +#include +#include + +/* EXTERNAL */ +#include + +/* PACKAGE */ +#include +#include + +namespace { +/* ****************************************************************************************************************** */ +using namespace fpsdk::common::parser::novb; + +TEST(ParserNovbTest, Macros) +{ + { + const uint8_t msg[] = { 0x55, 0x55, 0x55, 0x55, 0x34, 0x12, 0xaa, 0xaa, 0xaa }; + ASSERT_EQ(NovbMsgId(msg), 0x1234); + } + + { + const uint8_t msg_long[] = { NOV_B_SYNC_1, NOV_B_SYNC_2, NOV_B_SYNC_3_LONG }; + ASSERT_TRUE(NovbIsLongHeader(msg_long)); + ASSERT_FALSE(NovbIsShortHeader(msg_long)); + } + + { + const uint8_t msg_short[] = { NOV_B_SYNC_1, NOV_B_SYNC_2, NOV_B_SYNC_3_SHORT }; + ASSERT_FALSE(NovbIsLongHeader(msg_short)); + ASSERT_TRUE(NovbIsShortHeader(msg_short)); + } + + { + const uint8_t msg_neither[] = { NOV_B_SYNC_1, NOV_B_SYNC_2, 0xaa }; + ASSERT_FALSE(NovbIsLongHeader(msg_neither)); + ASSERT_FALSE(NovbIsShortHeader(msg_neither)); + } +} + +// --------------------------------------------------------------------------------------------------------------------- + +TEST(ParserNovbTest, NovbGetMessageName) +{ + // Known message + { + const uint8_t msg[] = { // clang-format off + NOV_B_SYNC_1, NOV_B_SYNC_2, NOV_B_SYNC_3_SHORT, 0x00, + (uint8_t)(NOV_B_BESTGNSSPOS_MSGID & 0xff), (uint8_t)((NOV_B_BESTGNSSPOS_MSGID >> 8) & 0xff), + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00 }; // clang-format on + char str[100]; + EXPECT_TRUE(NovbGetMessageName(str, sizeof(str), msg, sizeof(msg))); + EXPECT_EQ(std::string(str), std::string("NOV_B-BESTGNSSPOS")); + } + + // Unknown message + { + const uint8_t msg[] = { // clang-format off + NOV_B_SYNC_1, NOV_B_SYNC_2, NOV_B_SYNC_3_SHORT, 0x00, + 0x34, 0x12, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00 }; // clang-format on + char str[100]; + EXPECT_TRUE(NovbGetMessageName(str, sizeof(str), msg, sizeof(msg))); + EXPECT_EQ(std::string(str), std::string("NOV_B-MSG04660")); + } + + // Bad arguments + { + const uint8_t msg[] = { // clang-format off + NOV_B_SYNC_1, NOV_B_SYNC_2, NOV_B_SYNC_3_SHORT, 0x00, + 0x34, 0x12, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00 }; // clang-format on + char str[100]; + EXPECT_FALSE(NovbGetMessageName(str, 0, msg, sizeof(msg))); + EXPECT_FALSE(NovbGetMessageName(NULL, 10, msg, sizeof(msg))); + EXPECT_FALSE(NovbGetMessageName(NULL, 0, msg, sizeof(msg))); + EXPECT_FALSE(NovbGetMessageName(str, sizeof(str), msg, 0)); + EXPECT_FALSE(NovbGetMessageName(str, sizeof(str), msg, 5)); + EXPECT_FALSE(NovbGetMessageName(str, sizeof(str), NULL, sizeof(msg))); + } + + // Too small string is cut + { + const uint8_t msg[] = { // clang-format off + NOV_B_SYNC_1, NOV_B_SYNC_2, NOV_B_SYNC_3_SHORT, 0x00, + (uint8_t)(NOV_B_BESTGNSSPOS_MSGID & 0xff), (uint8_t)((NOV_B_BESTGNSSPOS_MSGID >> 8) & 0xff), + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00 }; // clang-format on + char str[10]; + EXPECT_FALSE(NovbGetMessageName(str, sizeof(str), msg, sizeof(msg))); + EXPECT_EQ(std::string(str), std::string("NOV_B-BES")); + } +} + +// --------------------------------------------------------------------------------------------------------------------- + +TEST(ParserNovbTest, NovbRawdmi) +{ + NovbRawdmi rawdmi; + std::memset(&rawdmi, 0, sizeof(rawdmi)); + rawdmi.dmi1 = 0x12345678; + rawdmi.dmi1_valid = 1; + uint8_t bytes[sizeof(rawdmi)]; + std::memcpy(bytes, &rawdmi, sizeof(bytes)); + EXPECT_EQ(bytes[0], 0x78); + EXPECT_EQ(bytes[1], 0x56); + EXPECT_EQ(bytes[2], 0x34); + EXPECT_EQ(bytes[3], 0x12); + EXPECT_EQ(bytes[16], 0x01); +} + +/* ****************************************************************************************************************** */ +} // namespace + +int main(int argc, char** argv) +{ + testing::InitGoogleTest(&argc, argv); + auto level = fpsdk::common::logging::LoggingLevel::WARNING; + for (int ix = 0; ix < argc; ix++) { + if ((argv[ix][0] == '-') && argv[ix][1] == 'v') { + level++; + } + } + fpsdk::common::logging::LoggingSetParams(level); + return RUN_ALL_TESTS(); +} diff --git a/fpsdk_common/test/parser_rtcm3_test.cpp b/fpsdk_common/test/parser_rtcm3_test.cpp new file mode 100644 index 0000000..a530393 --- /dev/null +++ b/fpsdk_common/test/parser_rtcm3_test.cpp @@ -0,0 +1,154 @@ +/** + * \verbatim + * ___ ___ + * \ \ / / + * \ \/ / Copyright (c) Fixposition AG (www.fixposition.com) and contributors + * / /\ \ License: see the LICENSE file + * /__/ \__\ + * \endverbatim + * + * @file + * @brief Fixposition SDK: tests for fpsdk::common::parser::rtcm3 + */ + +/* LIBC/STL */ +#include +#include +#include + +/* EXTERNAL */ +#include + +/* PACKAGE */ +#include +#include + +namespace { +/* ****************************************************************************************************************** */ +using namespace fpsdk::common::parser::rtcm3; + +static const std::vector gps_msm4 = { 0xd3, 0x00, 0x98, 0x43, 0x20, 0x00, 0x78, 0xae, 0x0b, 0x04, 0x00, 0x00, + 0x00, 0x2d, 0x43, 0xc0, 0x00, 0x00, 0x00, 0x00, 0x20, 0x00, 0x80, 0x00, 0x5d, 0xb7, 0xc9, 0xe9, 0x09, 0xc9, 0x09, + 0x69, 0xc9, 0xc8, 0x6a, 0x33, 0xd5, 0x44, 0x10, 0x64, 0xb1, 0x31, 0x20, 0xa5, 0x8f, 0x0a, 0x50, 0x05, 0x71, 0x31, + 0x82, 0x21, 0x41, 0xca, 0xea, 0x72, 0xd4, 0x12, 0x23, 0x0f, 0xf3, 0xf0, 0x98, 0x11, 0x3a, 0xe5, 0x2e, 0xc9, 0x86, + 0x9b, 0xc0, 0xff, 0x92, 0x14, 0x15, 0xae, 0x60, 0x88, 0x2f, 0x00, 0xae, 0xbf, 0xf6, 0x29, 0x6b, 0xc9, 0x3b, 0x60, + 0x27, 0x90, 0xbf, 0xcf, 0x57, 0x04, 0x12, 0xb0, 0x14, 0xbd, 0xa0, 0xb6, 0x0b, 0x82, 0x60, 0xb9, 0x0d, 0xb7, 0x73, + 0x3f, 0xeb, 0xfe, 0x43, 0xfe, 0xc2, 0xc0, 0x44, 0xfd, 0x51, 0xb9, 0x74, 0xcf, 0xb7, 0x45, 0x0d, 0x32, 0xc0, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0xed, 0xbc, 0xc4 }; + +static const std::vector type1005 = { 0xd3, 0x00, 0x13, 0x3e, 0xd0, 0x00, 0x03, 0x89, 0xf6, 0x1e, 0x1e, 0x8c, + 0x81, 0x7a, 0xdc, 0x05, 0xfc, 0x0a, 0xe0, 0xee, 0x82, 0xd0, 0xa1, 0xf9, 0xbf }; + +// --------------------------------------------------------------------------------------------------------------------- + +TEST(ParserRtcm3Test, Macros) +{ + const uint8_t msg[] = { 0x55, 0x55, 0x55, 0x12, 0x34, 0x56, 0xaa, 0xaa, 0xaa }; + ASSERT_EQ(Rtcm3Type(msg), 0x0123); + ASSERT_EQ(Rtcm3SubType(msg), 0x0456); +} + +// --------------------------------------------------------------------------------------------------------------------- + +TEST(ParserRtcm3Test, Rtcm3GetMessageName) +{ + // RTCM3 type 1234 + { + const uint8_t msg[] = { 0x55, 0x55, 0x55, 0x4d, 0x20, 0xaa, 0xaa, 0xaa, 0xaa }; + ASSERT_EQ(Rtcm3Type(msg), 1234); + char str[100]; + ASSERT_TRUE(Rtcm3GetMessageName(str, sizeof(str), msg, sizeof(msg))); + ASSERT_EQ(std::string(str), std::string("RTCM3-TYPE1234")); + } + + // RTCM3 type 4072, subtype 1 + { + const uint8_t msg[] = { 0x55, 0x55, 0x55, 0xfe, 0x80, 0x01, 0xaa, 0xaa, 0xaa }; + ASSERT_EQ(Rtcm3Type(msg), 4072); + ASSERT_EQ(Rtcm3SubType(msg), 1); + char str[100]; + ASSERT_TRUE(Rtcm3GetMessageName(str, sizeof(str), msg, sizeof(msg))); + ASSERT_EQ(std::string(str), std::string("RTCM3-TYPE4072_1")); + } + + // Bad input + { + const uint8_t msg[] = { RTCM3_PREAMBLE, 0x12, 0x34, 0x56, 0x78, 0x9a }; + char name[100]; + EXPECT_FALSE(Rtcm3GetMessageName(name, sizeof(name), NULL, 0)); + EXPECT_FALSE(Rtcm3GetMessageName(name, sizeof(name), msg, 0)); + EXPECT_FALSE(Rtcm3GetMessageName(NULL, 0, msg, sizeof(msg))); + EXPECT_FALSE(Rtcm3GetMessageName(name, 0, msg, sizeof(msg))); + } +} + +// --------------------------------------------------------------------------------------------------------------------- + +TEST(ParserRtcm3Test, Rtcm3GetTypeDesc) +{ + EXPECT_TRUE(Rtcm3GetTypeDesc(999) == NULL); + EXPECT_TRUE(Rtcm3GetTypeDesc(RTCM3_TYPE1001_MSGID) != NULL); + EXPECT_TRUE(Rtcm3GetTypeDesc(RTCM3_TYPE4072_MSGID, RTCM3_TYPE4072_1_SUBID) != NULL); + const std::string str = Rtcm3GetTypeDesc(RTCM3_TYPE1074_MSGID); + DEBUG("str=%s", str.c_str()); + EXPECT_GT(str.size(), 10); +} + +// --------------------------------------------------------------------------------------------------------------------- + +TEST(ParserRtcm3Test, Rtcm3GetArp) +{ + Rtcm3Arp arp; + EXPECT_FALSE(Rtcm3GetArp(NULL, arp)); + EXPECT_TRUE(Rtcm3GetArp(type1005.data(), arp)); + EXPECT_EQ(arp.ref_sta_id_, 0); + EXPECT_NEAR(arp.ecef_x_, 4278387.47, 1e-4); + EXPECT_NEAR(arp.ecef_y_, 635620.71, 1e-4); + EXPECT_NEAR(arp.ecef_z_, 4672340.04, 1e-4); +} + +// --------------------------------------------------------------------------------------------------------------------- + +TEST(ParserRtcm3Test, Rtcm3TypeToMsm) +{ + Rtcm3MsmGnss msm_gnss; + Rtcm3MsmType msm_type; + EXPECT_TRUE(Rtcm3TypeToMsm(RTCM3_TYPE1074_MSGID, msm_gnss, msm_type)); + EXPECT_EQ(msm_gnss, Rtcm3MsmGnss::GPS); + EXPECT_EQ(msm_type, Rtcm3MsmType::MSM4); +} + +// --------------------------------------------------------------------------------------------------------------------- + +TEST(ParserRtcm3Test, Rtcm3GetMsmHeader) +{ + Rtcm3MsmHeader msm; + EXPECT_FALSE(Rtcm3GetMsmHeader(NULL, msm)); + EXPECT_TRUE(Rtcm3GetMsmHeader(gps_msm4.data(), msm)); + EXPECT_EQ(msm.gnss_, Rtcm3MsmGnss::GPS); + EXPECT_EQ(msm.msm_, Rtcm3MsmType::MSM4); + EXPECT_EQ(msm.msg_type_, RTCM3_TYPE1074_MSGID); + EXPECT_EQ(msm.ref_sta_id_, 0); + EXPECT_NEAR(msm.any_tow_, 506168.001, 1e-4); + EXPECT_FALSE(msm.multi_msg_bit_); + EXPECT_EQ(msm.num_sat_, 9); + EXPECT_EQ(msm.num_sig_, 2); + EXPECT_EQ(msm.num_cell_, 18); +} + +/* ****************************************************************************************************************** */ +} // namespace + +int main(int argc, char** argv) +{ + testing::InitGoogleTest(&argc, argv); + auto level = fpsdk::common::logging::LoggingLevel::WARNING; + for (int ix = 0; ix < argc; ix++) { + if ((argv[ix][0] == '-') && argv[ix][1] == 'v') { + level++; + } + } + fpsdk::common::logging::LoggingSetParams(level); + return RUN_ALL_TESTS(); +} diff --git a/fpsdk_common/test/parser_spartn_test.cpp b/fpsdk_common/test/parser_spartn_test.cpp new file mode 100644 index 0000000..fc3bea4 --- /dev/null +++ b/fpsdk_common/test/parser_spartn_test.cpp @@ -0,0 +1,96 @@ +/** + * \verbatim + * ___ ___ + * \ \ / / + * \ \/ / Copyright (c) Fixposition AG (www.fixposition.com) and contributors + * / /\ \ License: see the LICENSE file + * /__/ \__\ + * \endverbatim + * + * @file + * @brief Fixposition SDK: tests for fpsdk::common::parser::spartn + */ + +/* LIBC/STL */ +#include + +/* EXTERNAL */ +#include + +/* PACKAGE */ +#include +#include + +namespace { +/* ****************************************************************************************************************** */ +using namespace fpsdk::common::parser::spartn; + +TEST(ParserSpartnTest, Macros) +{ + const uint8_t msg[] = { 0x00, 0xfe, 0x00, 0x00, 0xf0, 0x00, 0x00, 0x00, 0x00, 0x00 }; + ASSERT_EQ(SpartnType(msg), 0x7f); + ASSERT_EQ(SpartnSubType(msg), 0x0f); +} + +// --------------------------------------------------------------------------------------------------------------------- + +TEST(ParserSpartnTest, SpartnGetMessageName) +{ + // Known message (type 1, subtype 2) + { + const uint8_t msg[] = { // clang-format off + 0x73, 0x01 | (SPARTN_HPAC_MSGID << 1), 0x50, 0x67, 0x08 | (SPARTN_HPAC_GAL_SUBID << 4), + 0xb9, 0xa0, 0x3e, 0xd0, 0x5b}; // clang-format on + ASSERT_EQ(SpartnType(msg), SPARTN_HPAC_MSGID); + ASSERT_EQ(SpartnSubType(msg), SPARTN_HPAC_GAL_SUBID); + char str[100]; + ASSERT_TRUE(SpartnGetMessageName(str, sizeof(str), msg, sizeof(msg))); + ASSERT_EQ(std::string(str), std::string("SPARTN-HPAC-GAL")); + } + // Unknown message (type 42, subtype 3) + { + const uint8_t msg[] = { 0x73, 0x54, 0x50, 0x67, 0x38, 0xb9, 0xa0, 0x3e, 0xd0, 0x5b }; + ASSERT_EQ(SpartnType(msg), 42); + ASSERT_EQ(SpartnSubType(msg), 3); + char str[100]; + ASSERT_TRUE(SpartnGetMessageName(str, sizeof(str), msg, sizeof(msg))); + ASSERT_EQ(std::string(str), std::string("SPARTN-42-3")); + } + // Unknown subtype (type 42, subtype 3) + { + const uint8_t msg[] = { // clang-format off + 0x73, 0x01 | (SPARTN_PROP_MSGID << 1), 0x50, 0x67, 0x08 | (7 << 4), + 0xb9, 0xa0, 0x3e, 0xd0, 0x5b}; // clang-format on + ASSERT_EQ(SpartnType(msg), SPARTN_PROP_MSGID); + ASSERT_EQ(SpartnSubType(msg), 7); + char str[100]; + ASSERT_TRUE(SpartnGetMessageName(str, sizeof(str), msg, sizeof(msg))); + ASSERT_EQ(std::string(str), std::string("SPARTN-PROP-7")); + } + + // Bad input + { + const uint8_t msg[] = { SPARTN_PREAMBLE, 0x12, 0x34, 0x56, 0x78, 0x9a }; + char name[100]; + EXPECT_FALSE(SpartnGetMessageName(name, sizeof(name), NULL, 0)); + EXPECT_FALSE(SpartnGetMessageName(name, sizeof(name), msg, 0)); + EXPECT_FALSE(SpartnGetMessageName(NULL, 0, msg, sizeof(msg))); + EXPECT_FALSE(SpartnGetMessageName(name, 0, msg, sizeof(msg))); + } +} + +/* ****************************************************************************************************************** */ +} // namespace + +int main(int argc, char** argv) +{ + testing::InitGoogleTest(&argc, argv); + auto level = fpsdk::common::logging::LoggingLevel::WARNING; + for (int ix = 0; ix < argc; ix++) { + if ((argv[ix][0] == '-') && argv[ix][1] == 'v') { + level++; + } + } + fpsdk::common::logging::LoggingSetParams(level); + return RUN_ALL_TESTS(); +} diff --git a/fpsdk_common/test/parser_test.cpp b/fpsdk_common/test/parser_test.cpp index f1b75e9..2e8a030 100644 --- a/fpsdk_common/test/parser_test.cpp +++ b/fpsdk_common/test/parser_test.cpp @@ -8,26 +8,545 @@ * \endverbatim * * @file - * @brief Fixposition SDK: tests for fpsdk::common::stream + * @brief Fixposition SDK: tests for fpsdk::common::parser (Parser) */ /* LIBC/STL */ +#include +#include +#include #include +#include /* EXTERNAL */ #include /* PACKAGE */ #include -#include +#include namespace { /* ****************************************************************************************************************** */ -using namespace fpsdk::common::stream; +using namespace fpsdk::common::parser; -TEST(ParserTest, Dummy) +#include "data/test_data_fpa.cpp" +#include "data/test_data_fpb.cpp" +#include "data/test_data_mixed.cpp" +#include "data/test_data_nmea.cpp" +#include "data/test_data_novb.cpp" +#include "data/test_data_rtcm3.cpp" +#include "data/test_data_spartn.cpp" +#include "data/test_data_ubx.cpp" + +// --------------------------------------------------------------------------------------------------------------------- + +class ParserTest : public ::testing::Test +{ + public: + protected: + struct ExpectedMsgs + { + std::string name_; + std::vector data_; + }; + +#define _HELP1 "expected_msgs[" << msg_ix << "]" +#define _HELP2 "expected_flush[" << (msg_ix - expected_msgs.size()) << "]" + bool TestLog(Parser& parser, const std::vector& log_data, const std::vector& expected_msgs, + const std::vector& expected_flush) + { + ParserMsg msg; + bool res = true; + std::size_t msg_ix = -1; + + // Check all expected messages + std::size_t log_offs = 0; + while (log_offs < log_data.size()) { + uint8_t data[MAX_ANY_SIZE]; + const std::size_t size = std::min(sizeof(data), log_data.size() - log_offs); + std::memcpy(data, log_data.data() + log_offs, size); + log_offs += size; + EXPECT_TRUE(parser.Add(data, size)); + while (parser.Process(msg)) { + msg_ix++; + // We're expecting no less and no more + EXPECT_TRUE(msg_ix < expected_msgs.size()) << _HELP1; + EXPECT_EQ(msg_ix, msg.seq_ - 1) << _HELP1; + if (msg_ix < expected_msgs.size()) { + // Check name, size and data + EXPECT_EQ(std::string(msg.name_), expected_msgs[msg_ix].name_) << _HELP1; + EXPECT_EQ(msg.data_, expected_msgs[msg_ix].data_) << _HELP1; + } else { + res = false; + } + } + } + // Like above, with the remaining data at the end of the log (if there is any) + while (parser.Flush(msg)) { + msg_ix++; + EXPECT_TRUE(msg_ix < (expected_msgs.size() + expected_flush.size())) << _HELP2; + EXPECT_EQ(msg_ix, msg.seq_ - 1) << _HELP2; + if (msg_ix < (expected_msgs.size() + expected_flush.size())) { + EXPECT_EQ(std::string(msg.name_), expected_flush[msg_ix - expected_msgs.size()].name_) << _HELP2; + EXPECT_EQ(msg.data_, expected_flush[msg_ix - expected_msgs.size()].data_) << _HELP2; + } else { + res = false; + } + } + + return res; + } +#undef _HELP1 +#undef _HELP2 + + void TestDetector(const std::vector& data) + { + Parser parser; + ParserMsg msg; + // Not expecting anything from the parser until we have given the whole message + for (std::size_t ix = 0; ix < (data.size() - 1); ix++) { + const uint8_t b = data[ix]; + EXPECT_TRUE(parser.Add(&b, 1)); + EXPECT_FALSE(parser.Process(msg)); + } + // Feed the last byte + const uint8_t b = data[data.size() - 1]; + EXPECT_TRUE(parser.Add(&b, 1)); + EXPECT_TRUE(parser.Process(msg)); + // And there shouln't be anything more + EXPECT_FALSE(parser.Flush(msg)); + } + + void TestBadMessage(const std::vector& data) + { + Parser parser; + ParserMsg msg; + EXPECT_TRUE(parser.Add(data)); + std::size_t size = 0; + while (parser.Process(msg)) { + EXPECT_EQ(std::string(msg.name_), std::string("OTHER")); + size += msg.data_.size(); + } + while (parser.Flush(msg)) { + EXPECT_EQ(std::string(msg.name_), std::string("OTHER")); + size += msg.data_.size(); + } + EXPECT_EQ(size, data.size()); + } +}; + +// --------------------------------------------------------------------------------------------------------------------- + +TEST_F(ParserTest, Parser) { - EXPECT_TRUE(true); + Parser parser; + ParserMsg msg; + const std::vector garbage1 = { 0x11, 0x22, 0x11, 0x22, 0x11, 0x22, 0x11, 0x22, 0x11, 0x22 }; + const std::vector garbage2 = { 0x11, 0xaa, 0x11, 0xaa, 0x11, 0xaa, 0x11, 0xaa, 0x11, 0xaa }; + const std::vector nmea_gn_rmc = { // clang-format off + 0x24, 0x47, 0x4e, 0x52, 0x4d, 0x43, 0x2c, 0x31, 0x37, 0x34, 0x36, 0x34, 0x34, 0x2e, 0x32, 0x30, 0x2c, 0x41, + 0x2c, 0x34, 0x37, 0x32, 0x34, 0x2e, 0x30, 0x31, 0x38, 0x31, 0x38, 0x2c, 0x4e, 0x2c, 0x30, 0x30, 0x38, 0x32, + 0x37, 0x2e, 0x30, 0x32, 0x32, 0x34, 0x34, 0x2c, 0x45, 0x2c, 0x30, 0x2e, 0x30, 0x31, 0x33, 0x2c, 0x2c, 0x31, + 0x35, 0x30, 0x33, 0x32, 0x33, 0x2c, 0x2c, 0x2c, 0x52, 0x2c, 0x56, 0x2a, 0x30, 0x44, 0x0d, 0x0a }; // clang-format on + + // Add a valid message + parser.Reset(); + EXPECT_TRUE(parser.Add(nmea_gn_rmc)); + // We should get back exactly this message, and nothing more + EXPECT_TRUE(parser.Process(msg)); + EXPECT_EQ(msg.data_, nmea_gn_rmc); + EXPECT_FALSE(parser.Process(msg)); + + // Add some garbage that cannot be mistaken as an incomplete message of some known type + parser.Reset(); + EXPECT_TRUE(parser.Add(garbage1)); + // We should get back the garbage right away + EXPECT_TRUE(parser.Process(msg)); + EXPECT_EQ(msg.data_, garbage1); + + // Add some garbage that ends with the beginning of a (NOV_B) message + parser.Reset(); + EXPECT_TRUE(parser.Add(garbage2)); + // Even though it's all garbage, the parser is stuck in WAIT state + EXPECT_FALSE(parser.Process(msg)); + // Force-flushing it gives us the whole garbage + EXPECT_TRUE(parser.Flush(msg)); + EXPECT_EQ(msg.data_, garbage2); + // Similarly, we cann add more garbage to make it pass all data + EXPECT_TRUE(parser.Add(garbage2)); + EXPECT_FALSE(parser.Process(msg)); + EXPECT_TRUE(parser.Add(garbage1)); + EXPECT_TRUE(parser.Process(msg)); + EXPECT_EQ(std::vector(msg.data_.data(), msg.data_.data() + garbage2.size()), garbage2); + EXPECT_EQ( + std::vector(&msg.data_[garbage2.size()], &msg.data_[garbage2.size()] + garbage1.size()), garbage1); + + // Some garbage and a valid message + parser.Reset(); + EXPECT_TRUE(parser.Add(garbage1)); + EXPECT_TRUE(parser.Add(nmea_gn_rmc)); + EXPECT_TRUE(parser.Process(msg)); + EXPECT_EQ(msg.data_, garbage1); + EXPECT_TRUE(parser.Process(msg)); + EXPECT_EQ(msg.data_, nmea_gn_rmc); + + // Some maybe-a-message-garbage and a valid message + parser.Reset(); + EXPECT_TRUE(parser.Add(garbage2)); + EXPECT_FALSE(parser.Process(msg)); + EXPECT_TRUE(parser.Add(nmea_gn_rmc)); + EXPECT_TRUE(parser.Process(msg)); + EXPECT_EQ(msg.data_, garbage2); + EXPECT_TRUE(parser.Process(msg)); + EXPECT_EQ(msg.data_, nmea_gn_rmc); + + // Bad arguments + uint8_t data[] = { 0x55, 0xaa, 0x55, 0xaa }; + EXPECT_FALSE(parser.Add(NULL, 0)); + EXPECT_FALSE(parser.Add(NULL, -1)); + EXPECT_FALSE(parser.Add(data, 0)); + EXPECT_FALSE(parser.Add(data, -1)); + + // Overflow + std::vector too_large(MAX_ADD_SIZE * 10); + EXPECT_FALSE(parser.Add(too_large)); + // It should not have taken any of the data + EXPECT_FALSE(parser.Process(msg)); + EXPECT_FALSE(parser.Flush(msg)); +} + +// --------------------------------------------------------------------------------------------------------------------- + +TEST_F(ParserTest, FP_B) +{ + Parser parser; + EXPECT_TRUE( // clang-format off + TestLog(parser, TEST_DATA_FPB_BIN, { + { "FP_B-MEASUREMENTS", { 0x66, 0x21, 0xd1, 0x07, 0x5c, 0x00, 0x00, 0x00, 0x01, 0x03, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x0a, 0x00, 0x00, 0x00, 0x14, 0x00, 0x00, 0x00, 0xe2, 0xff, 0xff, 0xff, 0x01, 0x01, 0x01, 0x01, 0x01, 0x00, 0x00, 0x00, 0x00, 0x01, 0x0a, 0x00, 0x4e, 0x61, 0xbc, 0x00, 0x0b, 0x00, 0x00, 0x00, 0x15, 0x00, 0x00, 0x00, 0xe3, 0xff, 0xff, 0xff, 0x01, 0x01, 0x01, 0x01, 0x02, 0x00, 0x00, 0x00, 0x00, 0x01, 0x0a, 0x00, 0x4e, 0x61, 0xbc, 0x00, 0x0c, 0x00, 0x00, 0x00, 0x16, 0x00, 0x00, 0x00, 0xe4, 0xff, 0xff, 0xff, 0x01, 0x01, 0x01, 0x01, 0x03, 0x00, 0x00, 0x00, 0x00, 0x01, 0x0a, 0x00, 0x4e, 0x61, 0xbc, 0x00, 0x26, 0x54, 0xaa, 0x34 } } + }, { + })); // clang-format on + + // Exercise parser detector function + // clang-format off + TestDetector({0x66, 0x21, 0xea, 0xfd, 0x04, 0x00, 0x00, 0x00, 0x01, 0x02, 0x03, 0x04, 0x05, 0x70, 0x8c, 0xb8}); + TestBadMessage({0x67, 0x21, 0xea, 0xfd, 0x04, 0x00, 0x00, 0x00, 0x01, 0x02, 0x03, 0x04, 0x05, 0x70, 0x8c, 0xb8}); // bad sync char + TestBadMessage({0x66, 0x22, 0xea, 0xfd, 0x04, 0x00, 0x00, 0x00, 0x01, 0x02, 0x03, 0x04, 0x05, 0x70, 0x8c, 0xb8}); // bad sync char + TestBadMessage({0x66, 0x21, 0xea, 0xfd, 0xff, 0xff, 0x00, 0x00, 0x01, 0x02, 0x03, 0x04, 0x05, 0x70, 0x8c, 0xb8}); // too long payload + TestBadMessage({0x66, 0x21, 0xea, 0xfd, 0x04, 0x00, 0x00, 0x00, 0x01, 0x02, 0x03, 0x04, 0x05, 0x70, 0x8c, 0xb9}); // bad crc + // clang-format on +} + +// --------------------------------------------------------------------------------------------------------------------- + +TEST_F(ParserTest, UBX) +{ + Parser parser; + EXPECT_TRUE( // clang-format off + TestLog(parser, TEST_DATA_UBX_BIN, { + { "UBX-TIM-TP", { 0xb5, 0x62, 0x0d, 0x01, 0x10, 0x00, 0x88, 0xb7, 0x43, 0x13, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0xcd, 0x08, 0x1b, 0x3f, 0xe2, 0xd2 } }, + { "UBX-MON-HW", { 0xb5, 0x62, 0x0a, 0x09, 0x3c, 0x00, 0xc1, 0x81, 0x00, 0x00, 0x1e, 0x00, 0x01, 0x00, 0x00, 0x80, 0x00, 0x00, 0x4e, 0x66, 0x00, 0x00, 0x4f, 0x00, 0x0d, 0x1a, 0x02, 0x01, 0x01, 0x85, 0xbf, 0xff, 0x01, 0x00, 0x3e, 0x06, 0x07, 0x09, 0x08, 0x10, 0xff, 0x12, 0x13, 0x14, 0x15, 0x0e, 0x0a, 0x0b, 0x0f, 0x44, 0x16, 0x39, 0x0e, 0x5a, 0x00, 0x00, 0x00, 0x00, 0xc0, 0x7b, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0xc3, 0x0d } }, + { "UBX-MON-HW2", { 0xb5, 0x62, 0x0a, 0x0b, 0x1c, 0x00, 0x0c, 0x9e, 0x0c, 0x91, 0x00, 0x8a, 0xa9, 0xb8, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x57, 0x8e } }, + { "UBX-MON-TEMP", { 0xb5, 0x62, 0x0a, 0x0e, 0x0c, 0x00, 0x00, 0x00, 0x00, 0x00, 0x2f, 0x00, 0x01, 0x00, 0x00, 0x00, 0x00, 0x00, 0x54, 0x98 } }, + { "UBX-RXM-SFRBX", { 0xb5, 0x62, 0x02, 0x13, 0x30, 0x00, 0x00, 0x1b, 0x04, 0x00, 0x0a, 0x52, 0x02, 0x43, 0x93, 0xe6, 0x6d, 0x8b, 0xf8, 0x68, 0xb0, 0x71, 0x84, 0x18, 0x15, 0x64, 0x00, 0xb0, 0xb5, 0x7f, 0xfe, 0xe6, 0x0f, 0x04, 0xc6, 0x60, 0x1d, 0xe8, 0x00, 0xfe, 0x01, 0x1c, 0x02, 0xfc, 0x00, 0x3f, 0x85, 0xec, 0x1b, 0xcd, 0xe1, 0xb6, 0xe8, 0xba, 0xfc, 0xb6 } }, + { "UBX-RXM-SFRBX", { 0xb5, 0x62, 0x02, 0x13, 0x30, 0x00, 0x00, 0x0a, 0x04, 0x00, 0x0a, 0x57, 0x02, 0x43, 0x93, 0xe6, 0x29, 0x8b, 0xf8, 0x68, 0xf2, 0x71, 0x04, 0x7c, 0xf8, 0x65, 0x00, 0x08, 0xf2, 0x7f, 0x7f, 0xf6, 0x0f, 0x05, 0x76, 0x81, 0x2c, 0x80, 0x00, 0xfe, 0x01, 0x1c, 0x02, 0xfc, 0x00, 0x3f, 0x23, 0x00, 0xfa, 0xcd, 0xa1, 0xb2, 0x58, 0xa2, 0xfa, 0xcf } }, + { "UBX-RXM-SFRBX", { 0xb5, 0x62, 0x02, 0x13, 0x30, 0x00, 0x00, 0x12, 0x04, 0x00, 0x0a, 0x5f, 0x02, 0x43, 0x93, 0xe6, 0x49, 0x8b, 0x78, 0xed, 0xf3, 0x71, 0x6e, 0x91, 0xd0, 0x65, 0x01, 0xc0, 0x6f, 0xff, 0x82, 0xfe, 0x0f, 0xee, 0xe0, 0x7f, 0xfc, 0xcf, 0x00, 0xfe, 0x01, 0x1c, 0x02, 0xfc, 0x00, 0x3f, 0x99, 0x0a, 0x00, 0xcd, 0xa1, 0xb4, 0x98, 0xb1, 0x8f, 0x4e } }, + { "UBX-RXM-SFRBX", { 0xb5, 0x62, 0x02, 0x13, 0x30, 0x00, 0x00, 0x17, 0x04, 0x00, 0x0a, 0x60, 0x02, 0x43, 0x93, 0xe6, 0x5d, 0x8b, 0x78, 0xe9, 0xb1, 0x71, 0x9a, 0xd4, 0x02, 0x64, 0x01, 0x40, 0x12, 0x00, 0x83, 0xfc, 0x0f, 0xee, 0xef, 0xdf, 0xfd, 0x07, 0x00, 0xfe, 0x01, 0x1c, 0x02, 0xfc, 0x00, 0x3f, 0x31, 0x0d, 0x00, 0xcd, 0xe1, 0xb5, 0x68, 0xdf, 0xa8, 0x35 } }, + { "UBX-RXM-SFRBX", { 0xb5, 0x62, 0x02, 0x13, 0x30, 0x00, 0x00, 0x01, 0x04, 0x00, 0x0a, 0x61, 0x02, 0x43, 0x93, 0xe6, 0x05, 0x8b, 0x78, 0xed, 0xdb, 0x71, 0xb0, 0x16, 0x35, 0x64, 0x00, 0x90, 0xde, 0x7f, 0x7e, 0xfa, 0x0f, 0x0a, 0xfa, 0xe0, 0x1e, 0xa4, 0x00, 0xfe, 0x01, 0x1c, 0x02, 0xfc, 0x00, 0x3f, 0x46, 0x1b, 0x5d, 0xcd, 0x61, 0xb0, 0x28, 0x15, 0x5e, 0xc4 } }, + { "UBX-RXM-SFRBX", { 0xb5, 0x62, 0x02, 0x13, 0x30, 0x00, 0x00, 0x08, 0x04, 0x00, 0x0a, 0x63, 0x02, 0x43, 0x93, 0xe6, 0x21, 0x8b, 0x78, 0xec, 0x17, 0x72, 0x63, 0x5c, 0xe2, 0x61, 0x00, 0xd8, 0xef, 0xff, 0x7d, 0xeb, 0x0f, 0x0b, 0xc9, 0x60, 0x16, 0x1c, 0x00, 0xfe, 0x01, 0x1c, 0x02, 0xfc, 0x00, 0x3f, 0xd8, 0xa3, 0xee, 0xcd, 0x21, 0xb2, 0x88, 0x26, 0xc9, 0x59 } }, + { "UBX-RXM-RAWX", { 0xb5, 0x62, 0x02, 0x15, 0xd0, 0x08, 0xd9, 0xce, 0xf7, 0xd3, 0x58, 0xba, 0x13, 0x41, 0xcd, 0x08, 0x12, 0x46, 0x01, 0x01, 0xf0, 0x75, 0xde, 0x26, 0x6f, 0x09, 0x0d, 0xf3, 0x7b, 0x41, 0x80, 0x83, 0xfb, 0x04, 0x02, 0x5c, 0xa2, 0x41, 0xc2, 0x12, 0x12, 0x45, 0x02, 0x07, 0x00, 0x00, 0xf4, 0xfb, 0x26, 0x04, 0x02, 0x07, 0x07, 0x00, 0x4a, 0xe5, 0x15, 0x3a, 0x9b, 0xbc, 0x77, 0x41, 0x4b, 0x97, 0x61, 0x8c, 0x31, 0x2f, 0x9f, 0x41, 0x84, 0xc0, 0x6c, 0xc5, 0x00, 0x10, 0x00, 0x00, 0xf4, 0xfb, 0x29, 0x04, 0x02, 0x07, 0x0f, 0x00, 0x9d, 0x8f, 0x5e, 0x84, 0x52, 0xbc, 0x7b, 0x41, 0xf8, 0x30, 0x4c, 0xc7, 0x0d, 0x38, 0xa2, 0x41, 0x2a, 0xf0, 0x60, 0xc5, 0x02, 0x15, 0x00, 0x00, 0xf4, 0xfb, 0x26, 0x04, 0x02, 0x07, 0x07, 0x00, 0xa7, 0x4e, 0x91, 0xed, 0xb9, 0xb8, 0x79, 0x41, 0xdd, 0x32, 0xc8, 0xc1, 0x5e, 0xe5, 0xa0, 0x41, 0xcb, 0xa3, 0x22, 0x45, 0x00, 0x20, 0x00, 0x00, 0xf4, 0xfb, 0x27, 0x05, 0x02, 0x07, 0x07, 0x00, 0x59, 0xb3, 0x78, 0x6b, 0x9a, 0x11, 0x7a, 0x41, 0xa5, 0xd4, 0x65, 0xb4, 0xc0, 0x1f, 0xa1, 0x41, 0x89, 0x9f, 0x15, 0xc5, 0x02, 0x0d, 0x00, 0x00, 0xf4, 0xfb, 0x2a, 0x04, 0x02, 0x06, 0x07, 0x00, 0xf0, 0x55, 0x81, 0x36, 0x74, 0x42, 0x78, 0x41, 0xdc, 0x8f, 0x0f, 0xab, 0x0a, 0xdf, 0x9f, 0x41, 0xf0, 0xd3, 0x45, 0xc3, 0x02, 0x1a, 0x00, 0x00, 0xf4, 0xfb, 0x2d, 0x03, 0x01, 0x05, 0x07, 0x00, 0x00, 0xb3, 0x62, 0xe6, 0x30, 0x25, 0x84, 0x41, 0x7a, 0xaa, 0x50, 0x26, 0xb6, 0x39, 0xaa, 0x41, 0x38, 0x70, 0xba, 0xc4, 0x03, 0x0d, 0x00, 0x00, 0xf4, 0xfb, 0x25, 0x05, 0x03, 0x07, 0x07, 0x00, 0x17, 0xed, 0x9c, 0x69, 0xe1, 0x99, 0x84, 0x41, 0xf4, 0x93, 0xc6, 0xd2, 0x9e, 0xd1, 0xaa, 0x41, 0xbe, 0x87, 0xcc, 0xc4, 0x03, 0x08, 0x00, 0x00, 0xf4, 0xfb, 0x20, 0x06, 0x06, 0x08, 0x0f, 0x00, 0x2a, 0x81, 0xd2, 0x2c, 0x46, 0x12, 0x78, 0x41, 0x76, 0x47, 0x56, 0x18, 0x25, 0x56, 0x9f, 0x41, 0x5c, 0x8d, 0xfe, 0x44, 0x03, 0x14, 0x00, 0x00, 0xf4, 0xfb, 0x2d, 0x03, 0x01, 0x06, 0x07, 0x00, 0x6f, 0xba, 0xcb, 0xc3, 0xfb, 0x6d, 0x79, 0x41, 0xc4, 0x07, 0x26, 0x60, 0x66, 0x8d, 0xa0, 0x41, 0xcd, 0x37, 0x0c, 0x45, 0x03, 0x23, 0x00, 0x00, 0xf4, 0xfb, 0x27, 0x04, 0x02, 0x07, 0x07, 0x00, 0x4d, 0x64, 0x4b, 0xe8, 0x5a, 0x8a, 0x78, 0x41, 0x5c, 0xba, 0xeb, 0xce, 0x77, 0xf2, 0x9f, 0x41, 0x5c, 0x28, 0x8c, 0xc4, 0x03, 0x20, 0x00, 0x00, 0xf4, 0xfb, 0x2d, 0x03, 0x01, 0x06, 0x0f, 0x00, 0x6d, 0xbc, 0x48, 0xe6, 0x89, 0x2b, 0x78, 0x41, 0xc6, 0xbb, 0x70, 0xab, 0x08, 0x77, 0x9f, 0x41, 0xfc, 0xc1, 0x1b, 0xc5, 0x03, 0x1e, 0x00, 0x00, 0xf4, 0xfb, 0x2d, 0x03, 0x01, 0x06, 0x07, 0x00, 0xd7, 0x22, 0xa2, 0xb1, 0xeb, 0x84, 0x78, 0x41, 0x53, 0x30, 0xf9, 0xcb, 0xcc, 0x5d, 0xa0, 0x41, 0xb7, 0x75, 0x95, 0xc5, 0x06, 0x0d, 0x00, 0x05, 0xf4, 0xfb, 0x1c, 0x08, 0x06, 0x08, 0x07, 0x00, 0xef, 0x43, 0x21, 0x05, 0x86, 0x5d, 0x77, 0x41, 0xb3, 0x43, 0xd4, 0x04, 0xad, 0x39, 0x9f, 0x41, 0x1c, 0x9b, 0x6e, 0x45, 0x06, 0x01, 0x00, 0x08, 0xf4, 0xfb, 0x26, 0x06, 0x03, 0x07, 0x07, 0x00, 0xca, 0x68, 0x8e, 0xb5, 0x70, 0xba, 0x75, 0x41, 0x10, 0x5e, 0x5b, 0xf0, 0xa8, 0x16, 0x9d, 0x41, 0x44, 0xeb, 0x59, 0x44, 0x06, 0x08, 0x00, 0x0d, 0xf4, 0xfb, 0x2d, 0x05, 0x01, 0x06, 0x07, 0x00, 0xf1, 0x71, 0x8b, 0x44, 0xa0, 0xce, 0x78, 0x41, 0x6d, 0xd2, 0xfa, 0xfc, 0xee, 0x97, 0xa0, 0x41, 0x78, 0xb5, 0x33, 0x45, 0x06, 0x11, 0x00, 0x0b, 0x08, 0x9d, 0x24, 0x06, 0x03, 0x08, 0x07, 0x00, 0xd6, 0x24, 0xe5, 0x9a, 0x02, 0x55, 0x77, 0x41, 0x90, 0xae, 0x11, 0xce, 0x7d, 0x2b, 0x9f, 0x41, 0x24, 0xe5, 0xb2, 0x44, 0x06, 0x0f, 0x00, 0x07, 0xf4, 0xfb, 0x2a, 0x05, 0x02, 0x07, 0x0f, 0x00, 0xab, 0x8e, 0xc3, 0x9a, 0x9f, 0xe8, 0x78, 0x41, 0x91, 0x54, 0x5d, 0xe5, 0xda, 0x9e, 0xa0, 0x41, 0x0d, 0xdf, 0x66, 0xc5, 0x06, 0x16, 0x00, 0x04, 0xf4, 0xfb, 0x27, 0x06, 0x02, 0x07, 0x07, 0x00, 0x35, 0x98, 0xbb, 0x15, 0x9a, 0x2e, 0x83, 0x41, 0x82, 0x14, 0xcb, 0xd3, 0x58, 0x33, 0xa9, 0x41, 0x78, 0xe2, 0xd3, 0xc3, 0x01, 0x88, 0x00, 0x00, 0xf4, 0xfb, 0x29, 0x04, 0x02, 0x07, 0x0f, 0x00, 0x7a, 0x99, 0x39, 0x06, 0x80, 0xef, 0x75, 0x41, 0x74, 0xa3, 0x81, 0xc3, 0x6b, 0xd1, 0x9c, 0x41, 0x3c, 0x3b, 0x17, 0xc4, 0x00, 0x0a, 0x00, 0x00, 0xf4, 0xfb, 0x31, 0x03, 0x01, 0x05, 0x0f, 0x00, 0xe9, 0xb9, 0x44, 0x1e, 0x05, 0xe4, 0x83, 0x41, 0xc6, 0x4a, 0x46, 0xb6, 0xaf, 0x21, 0xaa, 0x41, 0xe8, 0x7c, 0xcf, 0xc3, 0x01, 0x7f, 0x00, 0x00, 0x50, 0xdc, 0x1f, 0x06, 0x05, 0x08, 0x0f, 0x00, 0x72, 0xd9, 0xbb, 0xf9, 0xad, 0x5c, 0x83, 0x41, 0x00, 0x2d, 0xee, 0xc6, 0xe1, 0x6f, 0xa9, 0x41, 0x10, 0xd9, 0xd4, 0xc3, 0x01, 0x7b, 0x00, 0x00, 0xf4, 0xfb, 0x27, 0x04, 0x02, 0x07, 0x0f, 0x00, 0x7a, 0xd2, 0x24, 0xc9, 0xfe, 0x3a, 0x77, 0x41, 0x77, 0x3d, 0x2d, 0x9d, 0xeb, 0x84, 0x9e, 0x41, 0x7b, 0x39, 0x31, 0xc5, 0x00, 0x17, 0x00, 0x00, 0xf4, 0xfb, 0x2c, 0x03, 0x01, 0x06, 0x07, 0x00, 0xcc, 0x1f, 0x95, 0x0c, 0xd2, 0xa6, 0x76, 0x41, 0x50, 0x45, 0x5c, 0xa2, 0xff, 0x7c, 0x9d, 0x41, 0xf1, 0x18, 0x59, 0x43, 0x03, 0x1d, 0x00, 0x00, 0xf4, 0xfb, 0x2f, 0x03, 0x01, 0x05, 0x07, 0x00, 0x09, 0x8f, 0xf1, 0xe4, 0xb0, 0x04, 0x7a, 0x41, 0xee, 0x99, 0x1c, 0xa6, 0x7e, 0xef, 0xa0, 0x41, 0x76, 0xb6, 0x39, 0xc5, 0x03, 0x2d, 0x00, 0x00, 0xf4, 0xfb, 0x28, 0x04, 0x02, 0x07, 0x07, 0x00, 0x27, 0x7e, 0xe9, 0x03, 0x6a, 0x15, 0x77, 0x41, 0x4d, 0x3a, 0x89, 0xf3, 0x64, 0xe4, 0x9e, 0x41, 0xcf, 0xd2, 0x2b, 0xc5, 0x06, 0x07, 0x00, 0x0c, 0xf4, 0xfb, 0x2b, 0x05, 0x01, 0x06, 0x0f, 0x00, 0xe0, 0x1d, 0xa4, 0x15, 0xb7, 0x16, 0x75, 0x41, 0x24, 0x4b, 0x28, 0x2c, 0xde, 0x33, 0x9c, 0x41, 0x83, 0xa2, 0xdc, 0xc4, 0x06, 0x17, 0x00, 0x0a, 0xf4, 0xfb, 0x2b, 0x05, 0x01, 0x06, 0x07, 0x00, 0x96, 0xb8, 0x46, 0xfd, 0xd0, 0x4c, 0x76, 0x41, 0x14, 0x0c, 0xb3, 0xab, 0xce, 0xb7, 0x9d, 0x41, 0xc1, 0xfa, 0x10, 0xc5, 0x06, 0x0e, 0x00, 0x00, 0xf4, 0xfb, 0x2a, 0x05, 0x01, 0x06, 0x0f, 0x00, 0xcd, 0x5d, 0xd7, 0xd5, 0xa3, 0x37, 0x75, 0x41, 0xc6, 0xc6, 0x3f, 0xe1, 0x5c, 0x5d, 0x9c, 0x41, 0x92, 0x12, 0xa3, 0x44, 0x06, 0x18, 0x00, 0x09, 0xf4, 0xfb, 0x2e, 0x05, 0x01, 0x06, 0x07, 0x00, 0xf4, 0xd2, 0x9b, 0xd9, 0x47, 0xc7, 0x7a, 0x41, 0x34, 0x4d, 0x20, 0xc6, 0x19, 0x97, 0xa1, 0x41, 0xd8, 0xd2, 0xce, 0x44, 0x02, 0x21, 0x00, 0x00, 0xf4, 0xfb, 0x28, 0x04, 0x02, 0x07, 0x07, 0x00, 0x1b, 0xa7, 0x9f, 0xc5, 0xdb, 0x5e, 0x7a, 0x41, 0xa6, 0x2c, 0xa8, 0xf8, 0x7f, 0x52, 0xa1, 0x41, 0x7f, 0x01, 0x71, 0xc4, 0x00, 0x1e, 0x00, 0x00, 0xf4, 0xfb, 0x26, 0x05, 0x02, 0x07, 0x0f, 0x00, 0xa5, 0x3b, 0x59, 0x8c, 0xad, 0x52, 0x77, 0x41, 0xca, 0xbb, 0xae, 0x1c, 0x0a, 0xa4, 0x9e, 0x41, 0xb8, 0x8d, 0xdc, 0x44, 0x00, 0x15, 0x00, 0x00, 0xf4, 0xfb, 0x2b, 0x04, 0x02, 0x06, 0x0f, 0x00, 0xcf, 0x1e, 0x77, 0x4f, 0xdf, 0x03, 0x7d, 0x41, 0xf3, 0xc0, 0x3d, 0xdd, 0x37, 0x0f, 0xa3, 0x41, 0xd4, 0xe7, 0xd6, 0xc4, 0x02, 0x03, 0x00, 0x00, 0xf4, 0xfb, 0x25, 0x04, 0x02, 0x07, 0x07, 0x00, 0x43, 0xeb, 0xfe, 0xec, 0x08, 0x7c, 0x79, 0x41, 0xfc, 0x61, 0xaf, 0x2a, 0x81, 0xbd, 0xa0, 0x41, 0x29, 0xbc, 0x01, 0xc5, 0x02, 0x01, 0x00, 0x00, 0xf4, 0xfb, 0x2c, 0x04, 0x01, 0x06, 0x07, 0x00, 0x59, 0x73, 0xb7, 0x5d, 0x17, 0xc9, 0x75, 0x41, 0xc6, 0x75, 0xe1, 0x8d, 0xf5, 0x9e, 0x9c, 0x41, 0x40, 0x20, 0x7e, 0x44, 0x00, 0x08, 0x00, 0x00, 0xf4, 0xfb, 0x2e, 0x03, 0x01, 0x05, 0x07, 0x00, 0xf4, 0x9c, 0xfc, 0xcb, 0x7b, 0x9d, 0x79, 0x41, 0xd3, 0xb3, 0x6c, 0xb1, 0x79, 0xd3, 0xa0, 0x41, 0x39, 0x9c, 0x63, 0xc5, 0x00, 0x12, 0x00, 0x00, 0xf4, 0xfb, 0x29, 0x04, 0x02, 0x07, 0x0f, 0x00, 0xb5, 0x6e, 0x7b, 0x6b, 0x6f, 0x46, 0x75, 0x41, 0x7d, 0xa1, 0xc4, 0xe7, 0x4d, 0xf3, 0x9b, 0x41, 0xae, 0xc0, 0xa0, 0xc4, 0x00, 0x1b, 0x00, 0x00, 0xf4, 0xfb, 0x2f, 0x03, 0x01, 0x05, 0x0f, 0x00, 0x46, 0xef, 0x15, 0xd0, 0x09, 0x89, 0x79, 0x41, 0xa7, 0x2b, 0xc7, 0x0d, 0x0c, 0xc6, 0xa0, 0x41, 0x70, 0xec, 0x3d, 0x45, 0x00, 0x01, 0x00, 0x00, 0xf4, 0xfb, 0x27, 0x05, 0x02, 0x07, 0x0f, 0x00, 0x83, 0x06, 0x3b, 0xe3, 0xd9, 0x0f, 0x7a, 0x41, 0x36, 0x6e, 0x47, 0x03, 0x9a, 0x1e, 0xa1, 0x41, 0x02, 0x93, 0x08, 0xc5, 0x00, 0x07, 0x00, 0x00, 0xf4, 0xfb, 0x1a, 0x06, 0x07, 0x08, 0x07, 0x00, 0x52, 0xda, 0x74, 0xb9, 0x41, 0xd2, 0x7a, 0x41, 0x0c, 0x02, 0x6d, 0xea, 0x4d, 0x9e, 0xa1, 0x41, 0x80, 0x4b, 0x63, 0x44, 0x02, 0x1f, 0x00, 0x00, 0xf4, 0xfb, 0x2a, 0x04, 0x01, 0x06, 0x07, 0x00, 0x74, 0x88, 0x81, 0x91, 0xfe, 0x4d, 0x7b, 0x41, 0x7f, 0x89, 0x52, 0x79, 0x95, 0xef, 0xa1, 0x41, 0x74, 0x9f, 0x0b, 0x44, 0x02, 0x08, 0x00, 0x00, 0xf4, 0xfb, 0x29, 0x04, 0x02, 0x06, 0x07, 0x00, 0x1f, 0xda, 0xb6, 0x4d, 0x74, 0x42, 0x78, 0x41, 0xa8, 0x84, 0x0d, 0x3f, 0xbc, 0x6b, 0x98, 0x41, 0x80, 0x90, 0x17, 0xc3, 0x02, 0x1a, 0x06, 0x00, 0xf4, 0xfb, 0x31, 0x03, 0x01, 0x04, 0x07, 0x00, 0xaf, 0x44, 0xd3, 0xb2, 0x9a, 0x11, 0x7a, 0x41, 0xda, 0x48, 0xef, 0x97, 0xf5, 0x3d, 0x9a, 0x41, 0x96, 0x4b, 0xe5, 0xc4, 0x02, 0x0d, 0x06, 0x00, 0xf4, 0xfb, 0x30, 0x03, 0x01, 0x04, 0x07, 0x00, 0x47, 0x19, 0x48, 0xec, 0x52, 0xbc, 0x7b, 0x41, 0x6a, 0x5f, 0xc5, 0xac, 0x82, 0xeb, 0x9b, 0x41, 0x30, 0x58, 0x2c, 0xc5, 0x02, 0x15, 0x06, 0x00, 0xf4, 0xfb, 0x29, 0x03, 0x02, 0x06, 0x07, 0x00, 0x3b, 0xa1, 0xe2, 0x21, 0x09, 0x7c, 0x79, 0x41, 0xf3, 0x2f, 0xce, 0xbf, 0x65, 0xa7, 0x99, 0x41, 0x72, 0xc8, 0xc6, 0xc4, 0x02, 0x01, 0x06, 0x00, 0xf4, 0xfb, 0x2f, 0x03, 0x01, 0x05, 0x07, 0x00, 0x17, 0xbc, 0xab, 0x35, 0xe1, 0x99, 0x84, 0x41, 0xf2, 0x60, 0x0c, 0x8b, 0xee, 0xbc, 0xa4, 0x41, 0xc8, 0x1e, 0x9e, 0xc4, 0x03, 0x08, 0x02, 0x00, 0xf4, 0xfb, 0x24, 0x04, 0x03, 0x07, 0x07, 0x00, 0xf6, 0x74, 0xa8, 0x71, 0x0d, 0xf3, 0x7b, 0x41, 0x44, 0x2f, 0xc1, 0x72, 0x9c, 0x22, 0x9c, 0x41, 0xc8, 0xd3, 0xdf, 0x44, 0x02, 0x07, 0x06, 0x00, 0xf4, 0xfb, 0x2a, 0x03, 0x02, 0x06, 0x07, 0x00, 0xd0, 0x5d, 0x47, 0xf7, 0x30, 0x25, 0x84, 0x41, 0xc9, 0xac, 0x40, 0xb2, 0x77, 0x47, 0xa4, 0x41, 0xb2, 0x27, 0x90, 0xc4, 0x03, 0x0d, 0x02, 0x00, 0xf4, 0xfb, 0x28, 0x04, 0x02, 0x07, 0x07, 0x00, 0x40, 0xaf, 0xd5, 0x9b, 0xdf, 0x03, 0x7d, 0x41, 0x73, 0x4f, 0x2e, 0x9b, 0x3e, 0x35, 0x9d, 0x41, 0x9f, 0xb4, 0xa4, 0xc4, 0x02, 0x03, 0x06, 0x00, 0xf4, 0xfb, 0x27, 0x03, 0x02, 0x07, 0x07, 0x00, 0x1a, 0x97, 0x37, 0x17, 0x48, 0xc7, 0x7a, 0x41, 0x30, 0xdb, 0x48, 0xc8, 0xdb, 0xf4, 0x9a, 0x41, 0x12, 0x7a, 0x9e, 0x44, 0x02, 0x21, 0x06, 0x00, 0xf4, 0xfb, 0x2f, 0x03, 0x01, 0x05, 0x07, 0x00, 0xa4, 0xfd, 0xb6, 0x0b, 0x42, 0xd2, 0x7a, 0x41, 0x2e, 0xdd, 0xe9, 0x8e, 0xe5, 0xff, 0x9a, 0x41, 0x64, 0x33, 0x2e, 0x44, 0x02, 0x1f, 0x06, 0x00, 0xf4, 0xfb, 0x2e, 0x03, 0x01, 0x05, 0x07, 0x00, 0xca, 0x06, 0x7e, 0xb3, 0xfe, 0x4d, 0x7b, 0x41, 0x9e, 0xbe, 0x0f, 0x6c, 0x75, 0x7c, 0x9b, 0x41, 0x78, 0x01, 0xd6, 0x43, 0x02, 0x08, 0x06, 0x00, 0xf4, 0xfb, 0x2a, 0x03, 0x02, 0x06, 0x07, 0x00, 0x23, 0x73, 0xeb, 0x5e, 0x6f, 0x46, 0x75, 0x41, 0x5f, 0xc8, 0x2f, 0x21, 0x90, 0xc7, 0x95, 0x41, 0x11, 0x83, 0x7a, 0xc4, 0x00, 0x1b, 0x03, 0x00, 0xf4, 0xfb, 0x2b, 0x04, 0x01, 0x06, 0x07, 0x00, 0x42, 0x05, 0xea, 0x24, 0x33, 0x3f, 0x7a, 0x41, 0xd1, 0xc6, 0x57, 0xfb, 0x7f, 0xde, 0x9a, 0x41, 0x9f, 0x7f, 0x46, 0xc5, 0x00, 0x1a, 0x03, 0x00, 0x00, 0x00, 0x0f, 0x09, 0x0f, 0x0c, 0x01, 0x00, 0xe0, 0x2f, 0xe6, 0x2a, 0xba, 0xb8, 0x79, 0x41, 0x85, 0xd0, 0x08, 0x34, 0xdb, 0x54, 0x9a, 0x41, 0x21, 0x7e, 0xfd, 0x44, 0x00, 0x20, 0x03, 0x00, 0xf4, 0xfb, 0x24, 0x05, 0x03, 0x08, 0x07, 0x00, 0x01, 0xb5, 0xac, 0xf7, 0x7f, 0xef, 0x75, 0x41, 0x02, 0x5c, 0xbe, 0xb5, 0xa4, 0x74, 0x96, 0x41, 0xb8, 0x97, 0xeb, 0xc3, 0x00, 0x0a, 0x03, 0x00, 0xf4, 0xfb, 0x2b, 0x04, 0x01, 0x06, 0x07, 0x00, 0x4c, 0xd8, 0x34, 0xe1, 0x9f, 0xe8, 0x78, 0x41, 0x66, 0xa1, 0xa6, 0xf8, 0xa8, 0xda, 0x99, 0x41, 0x7e, 0x8c, 0x33, 0xc5, 0x06, 0x16, 0x02, 0x04, 0xf4, 0xfb, 0x27, 0x06, 0x02, 0x07, 0x07, 0x00, 0x25, 0xf5, 0xcf, 0x47, 0xd1, 0x4c, 0x76, 0x41, 0x22, 0xc4, 0x12, 0xd0, 0x2d, 0x1d, 0x97, 0x41, 0x6a, 0x81, 0xe1, 0xc4, 0x06, 0x0e, 0x02, 0x00, 0xf4, 0xfb, 0x2a, 0x05, 0x01, 0x06, 0x0f, 0x00, 0x9d, 0x7e, 0xc9, 0x85, 0x86, 0x5d, 0x77, 0x41, 0x64, 0x0f, 0x99, 0x84, 0x4f, 0x49, 0x98, 0x41, 0xee, 0x8e, 0x39, 0x45, 0x06, 0x01, 0x02, 0x08, 0xf4, 0xfb, 0x22, 0x06, 0x04, 0x08, 0x07, 0x00, 0x75, 0x62, 0xb4, 0xdd, 0x02, 0x55, 0x77, 0x41, 0x3b, 0xc0, 0x85, 0xbb, 0x45, 0x3e, 0x98, 0x41, 0x3e, 0x28, 0x8b, 0x44, 0x06, 0x0f, 0x02, 0x07, 0xf4, 0xfb, 0x29, 0x05, 0x02, 0x07, 0x07, 0x00, 0x7d, 0x7a, 0x3e, 0xfa, 0xdb, 0x5e, 0x7a, 0x41, 0x64, 0x49, 0x93, 0x4d, 0xe9, 0xfe, 0x9a, 0x41, 0xf0, 0x04, 0x3c, 0xc4, 0x00, 0x1e, 0x03, 0x00, 0xf4, 0xfb, 0x20, 0x06, 0x05, 0x08, 0x0f, 0x00, 0x23, 0x8e, 0x44, 0xb8, 0x7b, 0x9d, 0x79, 0x41, 0xfe, 0xc4, 0xed, 0x80, 0xf2, 0x38, 0x9a, 0x41, 0x5c, 0x58, 0x31, 0xc5, 0x00, 0x12, 0x03, 0x00, 0xf4, 0xfb, 0x24, 0x05, 0x03, 0x08, 0x0f, 0x00, 0xf2, 0xd8, 0x32, 0xaf, 0xfe, 0x3a, 0x77, 0x41, 0x85, 0x0a, 0xa8, 0x63, 0xfd, 0xc7, 0x97, 0x41, 0x3f, 0x18, 0x0a, 0xc5, 0x00, 0x17, 0x03, 0x00, 0xf4, 0xfb, 0x2a, 0x04, 0x01, 0x06, 0x07, 0x00, 0x31, 0xa1, 0xe3, 0x42, 0x0a, 0x89, 0x79, 0x41, 0xb4, 0x05, 0x14, 0xf4, 0x05, 0x24, 0x9a, 0x41, 0x66, 0x09, 0x14, 0x45, 0x00, 0x01, 0x03, 0x00, 0xf4, 0xfb, 0x24, 0x05, 0x04, 0x08, 0x07, 0x00, 0xdc, 0x4b, 0xf4, 0x75, 0xd9, 0x0f, 0x7a, 0x41, 0x50, 0x59, 0x53, 0xec, 0x06, 0xae, 0x9a, 0x41, 0x2c, 0x6b, 0xd4, 0xc4, 0x00, 0x07, 0x03, 0x00, 0x00, 0x00, 0x16, 0x09, 0x0f, 0x0c, 0x01, 0x00, 0xcb, 0xa6, 0x17, 0x6d, 0x17, 0xc9, 0x75, 0x41, 0xd7, 0x2c, 0x19, 0xd3, 0x50, 0x4d, 0x96, 0x41, 0xd4, 0x0a, 0x46, 0x44, 0x00, 0x08, 0x03, 0x00, 0xf4, 0xfb, 0x2c, 0x04, 0x01, 0x06, 0x07, 0x00, 0x89, 0x46, 0xe8, 0x41, 0xec, 0x84, 0x78, 0x41, 0xb7, 0x12, 0xf9, 0xca, 0x76, 0x75, 0x99, 0x41, 0x0e, 0x77, 0x68, 0xc5, 0x06, 0x0d, 0x02, 0x05, 0xf4, 0xfb, 0x20, 0x07, 0x05, 0x08, 0x0f, 0x00, 0x73, 0x17, 0xf9, 0xba, 0x70, 0xba, 0x75, 0x41, 0x5d, 0xbb, 0x16, 0xe9, 0xda, 0x9f, 0x96, 0x41, 0xb9, 0x88, 0x29, 0x44, 0x06, 0x08, 0x02, 0x0d, 0xf4, 0xfb, 0x2a, 0x05, 0x02, 0x06, 0x07, 0x00, 0x74, 0xce, 0xda, 0xef, 0xa3, 0x37, 0x75, 0x41, 0x37, 0xbf, 0xfc, 0xb2, 0xbe, 0x0f, 0x96, 0x41, 0x2f, 0xb3, 0x7d, 0x44, 0x06, 0x18, 0x02, 0x09, 0xf4, 0xfb, 0x2c, 0x05, 0x01, 0x06, 0x07, 0x00, 0xc1, 0x45, 0x47, 0x27, 0x6a, 0x15, 0x77, 0x41, 0x47, 0xdb, 0xa1, 0x7a, 0xf7, 0x06, 0x98, 0x41, 0xf1, 0xa9, 0x05, 0xc5, 0x06, 0x07, 0x02, 0x0c, 0xf4, 0xfb, 0x27, 0x06, 0x02, 0x07, 0x07, 0x00, 0xa4, 0x8a } }, + { "UBX-MON-MSGPP", { 0xb5, 0x62, 0x0a, 0x06, 0x78, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x32, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0xa4, 0x9f, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x2e, 0x47, 0x06, 0x00, 0x00, 0x00, 0x00, 0x00, 0x78, 0xca } }, + { "UBX-MON-COMMS", { 0xb5, 0x62, 0x0a, 0x36, 0x80, 0x00, 0x00, 0x03, 0x00, 0x00, 0x00, 0x01, 0x05, 0x06, 0x00, 0x02, 0x00, 0x00, 0x32, 0x83, 0x0b, 0x05, 0x05, 0x0b, 0x00, 0x00, 0x19, 0x1c, 0xf2, 0x14, 0x06, 0x15, 0x00, 0x00, 0x24, 0xc0, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x85, 0x00, 0x00, 0x00, 0x00, 0x04, 0x18, 0x00, 0x07, 0x2b, 0x96, 0x0e, 0x0b, 0x37, 0x00, 0x00, 0x02, 0xc3, 0x67, 0x00, 0x06, 0x10, 0x00, 0x00, 0x32, 0x00, 0x00, 0x00, 0xa4, 0x9f, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x2e, 0x47, 0x06, 0x00, 0x01, 0x01, 0x00, 0x00, 0x1c, 0xed, 0xf1, 0x14, 0x08, 0x0a, 0x00, 0x00, 0x16, 0x3d, 0x02, 0x05, 0x06, 0x12, 0x00, 0x00, 0x69, 0x4f, 0x00, 0x00, 0xa4, 0x9f, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x5a, 0xcf } }, + { "UBX-MON-HW3", { 0xb5, 0x62, 0x0a, 0x37, 0xe2, 0x00, 0x00, 0x22, 0x01, 0x30, 0x30, 0x31, 0x39, 0x30, 0x30, 0x30, 0x30, 0x00, 0x00, 0x03, 0x0e, 0x5a, 0x0e, 0x5a, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x41, 0x08, 0x3e, 0x00, 0x00, 0x01, 0x64, 0x08, 0x06, 0x00, 0x00, 0x02, 0x44, 0x08, 0x07, 0x00, 0x00, 0x03, 0x64, 0x08, 0x09, 0x00, 0x00, 0x04, 0x44, 0x08, 0x08, 0x00, 0x00, 0x05, 0x40, 0x08, 0x10, 0x00, 0x00, 0x06, 0x21, 0x09, 0xff, 0x00, 0x00, 0x07, 0x41, 0x09, 0x12, 0x00, 0x00, 0x08, 0x41, 0x09, 0x13, 0x00, 0x00, 0x09, 0x60, 0x09, 0x14, 0x00, 0x00, 0x0a, 0x60, 0x08, 0x15, 0x00, 0x00, 0x0b, 0x40, 0x09, 0x0e, 0x00, 0x00, 0x0c, 0x40, 0x09, 0x0a, 0x00, 0x00, 0x0d, 0x60, 0x09, 0x0b, 0x00, 0x00, 0x0e, 0x60, 0x09, 0x0f, 0x00, 0x00, 0x0f, 0x51, 0x08, 0x44, 0x00, 0x00, 0x10, 0x44, 0x08, 0x16, 0x00, 0x01, 0x00, 0x21, 0x09, 0xff, 0x00, 0x01, 0x01, 0x60, 0x09, 0x00, 0x00, 0x01, 0x02, 0x60, 0x08, 0x01, 0x00, 0x01, 0x03, 0x21, 0x09, 0xff, 0x00, 0x01, 0x04, 0x51, 0x08, 0x46, 0x00, 0x01, 0x05, 0x21, 0x09, 0xff, 0x00, 0x01, 0x06, 0x21, 0x09, 0xff, 0x00, 0x01, 0x07, 0x41, 0x09, 0x12, 0x00, 0x01, 0x08, 0x61, 0x09, 0x13, 0x00, 0x01, 0x09, 0x60, 0x09, 0x14, 0x00, 0x01, 0x0a, 0x60, 0x08, 0x15, 0x00, 0x01, 0x0b, 0x21, 0x09, 0xff, 0x00, 0x01, 0x0c, 0x21, 0x09, 0xff, 0x00, 0x01, 0x0d, 0x21, 0x09, 0xff, 0x00, 0x01, 0x0e, 0x61, 0x09, 0x34, 0x00, 0x01, 0x0f, 0xe1, 0x09, 0x36, 0x00, 0x01, 0x10, 0x51, 0x08, 0x35, 0x00, 0x51, 0x82 } }, + { "UBX-MON-RF", { 0xb5, 0x62, 0x0a, 0x38, 0x34, 0x00, 0x00, 0x02, 0x00, 0x00, 0x00, 0x00, 0x02, 0x01, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x4f, 0x00, 0x0d, 0x1a, 0x2a, 0x0d, 0x9f, 0x07, 0x92, 0x00, 0x00, 0x00, 0x01, 0x00, 0x02, 0x01, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x33, 0x00, 0x0d, 0x1a, 0x23, 0x0f, 0x9f, 0x06, 0x9c, 0x00, 0x00, 0x00, 0x31, 0x79 } }, + { "UBX-MON-SPAN", { 0xb5, 0x62, 0x0a, 0x31, 0x24, 0x02, 0x00, 0x02, 0x00, 0x00, 0x48, 0x45, 0x43, 0x45, 0x47, 0x45, 0x45, 0x45, 0x47, 0x44, 0x48, 0x46, 0x48, 0x48, 0x47, 0x49, 0x48, 0x49, 0x49, 0x4a, 0x4c, 0x4d, 0x4d, 0x50, 0x4f, 0x4f, 0x50, 0x4f, 0x54, 0x53, 0x58, 0x66, 0xa7, 0x6c, 0x66, 0x57, 0x55, 0x58, 0x57, 0x5a, 0x53, 0x58, 0x58, 0x57, 0x57, 0x55, 0x5a, 0x5c, 0x5c, 0x63, 0x61, 0x64, 0x64, 0x63, 0x66, 0x69, 0x69, 0x66, 0x68, 0x6c, 0x6d, 0x6c, 0x6d, 0x6f, 0x77, 0x7a, 0x78, 0x78, 0x77, 0x79, 0x79, 0x7c, 0x7e, 0x7e, 0x7f, 0x80, 0x82, 0x82, 0x85, 0x88, 0x88, 0x8a, 0x89, 0x88, 0x86, 0x86, 0x87, 0x85, 0x86, 0x85, 0x93, 0x87, 0x86, 0x84, 0x85, 0x86, 0x9c, 0x86, 0x87, 0x85, 0x85, 0x84, 0x82, 0x83, 0x83, 0x84, 0x84, 0x84, 0x85, 0x8c, 0x90, 0x8d, 0x8d, 0x8c, 0x88, 0x87, 0x88, 0x89, 0x89, 0x8a, 0x8a, 0x92, 0x8c, 0x8d, 0x91, 0x90, 0x91, 0x98, 0x94, 0x92, 0x91, 0x92, 0x92, 0xb4, 0x95, 0x90, 0x8e, 0x8e, 0x8f, 0x8d, 0x8f, 0x8d, 0x8e, 0x8b, 0x8d, 0x88, 0x89, 0x88, 0x86, 0x86, 0x84, 0x85, 0x85, 0x81, 0x81, 0x83, 0x82, 0x84, 0x84, 0x87, 0xb4, 0x8b, 0x85, 0x84, 0x85, 0x84, 0x85, 0x85, 0x86, 0x88, 0x8a, 0x87, 0x86, 0x86, 0x86, 0x86, 0x88, 0x87, 0x83, 0x83, 0x82, 0x81, 0x7f, 0x7f, 0x7d, 0x7c, 0x7b, 0x78, 0x76, 0x75, 0x7b, 0x71, 0x71, 0x6c, 0x6a, 0x69, 0x66, 0x64, 0x63, 0x61, 0x62, 0x60, 0x60, 0x5e, 0x5d, 0x5d, 0x5a, 0x5a, 0x59, 0x59, 0x67, 0x57, 0x55, 0x54, 0x55, 0x54, 0x54, 0x53, 0x51, 0x4f, 0x57, 0x51, 0x5b, 0x4e, 0x54, 0x4e, 0x4b, 0x4b, 0x4a, 0x4c, 0x4a, 0x4b, 0x53, 0x4c, 0x49, 0x48, 0x48, 0x47, 0x48, 0x47, 0x46, 0x46, 0x45, 0x47, 0x46, 0x45, 0x44, 0x45, 0x44, 0x4d, 0x45, 0x46, 0x45, 0x45, 0x46, 0x46, 0x00, 0x20, 0xa1, 0x07, 0x20, 0xa1, 0x07, 0x00, 0x82, 0xb3, 0x61, 0x5e, 0x39, 0x00, 0x00, 0x00, 0x47, 0x48, 0x46, 0x48, 0x47, 0x46, 0x48, 0x48, 0x49, 0x48, 0x48, 0x49, 0x4a, 0x4a, 0x4a, 0x4d, 0x4b, 0x4c, 0x4b, 0x4c, 0x52, 0x4e, 0x4c, 0x4e, 0x50, 0x50, 0x4f, 0x53, 0x58, 0x57, 0x58, 0x54, 0x57, 0x5a, 0x59, 0x59, 0x5a, 0x5d, 0x5c, 0x5e, 0x60, 0x63, 0x63, 0x62, 0x63, 0x64, 0x65, 0x69, 0x68, 0x69, 0x6b, 0x6d, 0x6f, 0x72, 0x73, 0x76, 0x76, 0x79, 0x7c, 0x96, 0x7e, 0x7e, 0x80, 0x82, 0x84, 0x85, 0x85, 0x88, 0x89, 0x88, 0x89, 0x8c, 0x8a, 0x8a, 0x8a, 0x8a, 0x8b, 0x8b, 0x8e, 0xb1, 0x8d, 0x8d, 0x8c, 0x8c, 0x8c, 0x8a, 0x8c, 0x8e, 0x8c, 0x8b, 0x8d, 0x8e, 0x8e, 0x8d, 0x8c, 0x8f, 0x8e, 0x8d, 0x8b, 0x8b, 0x8c, 0x8c, 0x8b, 0x8c, 0x8c, 0x8b, 0x8d, 0x8d, 0x8b, 0x89, 0x89, 0x91, 0x8b, 0x8c, 0x8d, 0x8e, 0x8d, 0x8e, 0x8e, 0x8d, 0x8e, 0x8e, 0x8e, 0x8f, 0x90, 0x91, 0x94, 0xa4, 0x93, 0x92, 0x91, 0x8d, 0x8e, 0x8f, 0x91, 0x8e, 0x8d, 0x8d, 0x8d, 0x8c, 0x8c, 0x8d, 0x8c, 0x8c, 0x8a, 0x8b, 0x8a, 0x89, 0x89, 0x8b, 0x89, 0x88, 0x89, 0x89, 0x88, 0x89, 0x89, 0x89, 0xa3, 0x89, 0x89, 0x8a, 0x89, 0x89, 0x89, 0x89, 0x88, 0x89, 0x8b, 0x8b, 0x8a, 0x8a, 0x8b, 0x8c, 0x8b, 0x8e, 0x8b, 0x8a, 0x8c, 0x90, 0x8b, 0x8a, 0x89, 0x8a, 0x89, 0x88, 0x88, 0x86, 0x85, 0x85, 0x83, 0x81, 0x7e, 0x7d, 0x7b, 0x7a, 0x76, 0x75, 0x73, 0x70, 0x6f, 0x6e, 0x6a, 0x6a, 0x68, 0x68, 0x65, 0x63, 0x62, 0x5f, 0x5e, 0x5d, 0x5b, 0x59, 0x59, 0x59, 0x56, 0x55, 0x56, 0x53, 0x53, 0x50, 0x51, 0x50, 0x50, 0x51, 0x56, 0x4e, 0x4c, 0x4c, 0x4d, 0x4b, 0x4a, 0x4a, 0x4a, 0x4a, 0x4a, 0x49, 0x4a, 0x68, 0x4a, 0x48, 0x48, 0x4a, 0x48, 0x48, 0x47, 0x48, 0x47, 0x47, 0x46, 0x46, 0x46, 0x47, 0x47, 0x47, 0x00, 0x20, 0xa1, 0x07, 0x20, 0xa1, 0x07, 0x00, 0x6a, 0xda, 0xf4, 0x48, 0x39, 0x00, 0x00, 0x00, 0xe6, 0x81 } }, + { "UBX-RXM-SFRBX", { 0xb5, 0x62, 0x02, 0x13, 0x30, 0x00, 0x03, 0x1d, 0x00, 0x00, 0x0a, 0x18, 0x02, 0x00, 0xe4, 0x34, 0x90, 0x38, 0xf6, 0xe3, 0x08, 0x3a, 0xf6, 0x65, 0x4e, 0x24, 0x1e, 0x80, 0x28, 0x17, 0xc9, 0xfd, 0x77, 0x03, 0x4d, 0x00, 0x6a, 0x26, 0x49, 0xa2, 0x9f, 0x05, 0x78, 0xef, 0x44, 0x0f, 0x0b, 0x41, 0xf9, 0x02, 0xe2, 0x2c, 0xd9, 0x3c, 0xfe, 0x19 } }, + { "UBX-RXM-SFRBX", { 0xb5, 0x62, 0x02, 0x13, 0x30, 0x00, 0x03, 0x14, 0x00, 0x00, 0x0a, 0x08, 0x02, 0x00, 0xe4, 0x34, 0x90, 0x38, 0xf6, 0xe3, 0x08, 0x3a, 0xfa, 0x3b, 0x4f, 0x24, 0x44, 0x00, 0x0e, 0x02, 0x89, 0xfd, 0xb7, 0x02, 0xdb, 0xff, 0xd1, 0x2f, 0x8a, 0x9b, 0x81, 0x36, 0x31, 0x80, 0x11, 0x1a, 0xac, 0x0c, 0xe7, 0x3f, 0x44, 0xe4, 0x07, 0x05, 0x4a, 0x83 } }, + { "UBX-RXM-SFRBX", { 0xb5, 0x62, 0x02, 0x13, 0x30, 0x00, 0x03, 0x1e, 0x00, 0x00, 0x0a, 0x0b, 0x02, 0x00, 0xe4, 0x34, 0x90, 0x38, 0xf6, 0xe3, 0x08, 0x3a, 0xf5, 0x64, 0x4e, 0x24, 0xb3, 0x7f, 0x4c, 0x14, 0x99, 0xfd, 0x47, 0x3e, 0x99, 0x00, 0x94, 0x27, 0x73, 0xce, 0xbf, 0x0d, 0x74, 0x97, 0x45, 0x0f, 0x7b, 0x90, 0x70, 0x3b, 0x1f, 0xde, 0xa3, 0x19, 0x1f, 0x0d } }, + { "UBX-RXM-SFRBX", { 0xb5, 0x62, 0x02, 0x13, 0x30, 0x00, 0x03, 0x20, 0x00, 0x00, 0x0a, 0x0a, 0x02, 0x00, 0xe4, 0x34, 0x90, 0x38, 0xf6, 0xe3, 0x08, 0x3a, 0xf1, 0x20, 0x4f, 0x24, 0x1e, 0x80, 0x58, 0x2e, 0xa9, 0xfd, 0x9f, 0x01, 0xb0, 0x00, 0x80, 0x31, 0x77, 0x91, 0x81, 0x0b, 0xff, 0xbb, 0x08, 0x3a, 0x81, 0x7a, 0x86, 0x10, 0x6d, 0x7e, 0x26, 0x34, 0x2e, 0x2c } }, + { "UBX-NAV-PVT", { 0xb5, 0x62, 0x01, 0x07, 0x5c, 0x00, 0xb8, 0xfa, 0x43, 0x13, 0xe7, 0x07, 0x03, 0x0f, 0x11, 0x2e, 0x2c, 0x37, 0x15, 0x00, 0x00, 0x00, 0xb1, 0x03, 0xec, 0x0b, 0x03, 0x83, 0xea, 0x1d, 0xbd, 0x6c, 0x09, 0x05, 0x56, 0xb6, 0x40, 0x1c, 0x93, 0x02, 0x07, 0x00, 0xaa, 0x49, 0x06, 0x00, 0x0e, 0x00, 0x00, 0x00, 0x0e, 0x00, 0x00, 0x00, 0xf9, 0xff, 0xff, 0xff, 0x01, 0x00, 0x00, 0x00, 0xf5, 0xff, 0xff, 0xff, 0x07, 0x00, 0x00, 0x00, 0x90, 0xbe, 0xe4, 0x01, 0x45, 0x00, 0x00, 0x00, 0x80, 0xa8, 0x12, 0x01, 0x6c, 0x00, 0x04, 0x00, 0x5c, 0x41, 0x4f, 0x21, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0xcb, 0xa3 } }, + { "UBX-NAV-HPPOSECEF", { 0xb5, 0x62, 0x01, 0x13, 0x1c, 0x00, 0x00, 0x00, 0x00, 0x00, 0xb8, 0xfa, 0x43, 0x13, 0xec, 0x4c, 0x80, 0x19, 0x90, 0xe1, 0xc9, 0x03, 0xf7, 0x6c, 0xd9, 0x1b, 0x1c, 0xec, 0xf6, 0x00, 0xc8, 0x00, 0x00, 0x00, 0x63, 0xaa } }, + { "UBX-NAV-VELECEF", { 0xb5, 0x62, 0x01, 0x11, 0x14, 0x00, 0xb8, 0xfa, 0x43, 0x13, 0x01, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x07, 0x00, 0x00, 0x00, 0x36, 0x6a } }, + { "UBX-RXM-SFRBX", { 0xb5, 0x62, 0x02, 0x13, 0x30, 0x00, 0x03, 0x23, 0x00, 0x00, 0x0a, 0x09, 0x02, 0x00, 0xe4, 0x34, 0x90, 0x38, 0xf6, 0xe3, 0x08, 0x3a, 0xf9, 0x3f, 0x4e, 0x24, 0x5b, 0x00, 0xaf, 0x1b, 0x09, 0xfd, 0x5f, 0x04, 0xe6, 0xff, 0x93, 0x25, 0x89, 0x97, 0x5f, 0x3b, 0x48, 0x09, 0x48, 0x0f, 0xf5, 0x7a, 0x58, 0x1f, 0x6d, 0xa0, 0x44, 0x25, 0x0e, 0x01 } }, + { "UBX-NAV-SAT", { 0xb5, 0x62, 0x01, 0x35, 0x84, 0x02, 0xb8, 0xfa, 0x43, 0x13, 0x01, 0x35, 0x00, 0x00, 0x00, 0x01, 0x27, 0x07, 0x00, 0x01, 0xf2, 0xff, 0x17, 0x19, 0x00, 0x00, 0x00, 0x07, 0x1a, 0x04, 0x1c, 0x01, 0x00, 0x00, 0x17, 0x19, 0x00, 0x00, 0x00, 0x08, 0x2e, 0x3e, 0x2e, 0x01, 0x02, 0x00, 0x5f, 0x19, 0x32, 0x00, 0x00, 0x0a, 0x31, 0x40, 0x5f, 0x00, 0x05, 0x00, 0x5f, 0x19, 0x32, 0x00, 0x00, 0x0f, 0x00, 0x02, 0x18, 0x00, 0x00, 0x00, 0x11, 0x1a, 0x00, 0x00, 0x00, 0x10, 0x29, 0x23, 0xc1, 0x00, 0xfa, 0xff, 0x5f, 0x19, 0x32, 0x00, 0x00, 0x12, 0x29, 0x0a, 0x46, 0x00, 0xec, 0xff, 0x17, 0x19, 0x00, 0x00, 0x00, 0x15, 0x2b, 0x21, 0x09, 0x01, 0xfd, 0xff, 0x5f, 0x19, 0x32, 0x00, 0x00, 0x17, 0x2c, 0x25, 0x35, 0x00, 0xfa, 0xff, 0x5f, 0x19, 0x32, 0x00, 0x00, 0x1a, 0x09, 0x05, 0xaf, 0x00, 0x00, 0x00, 0x13, 0x19, 0x00, 0x00, 0x00, 0x1b, 0x2f, 0x50, 0x78, 0x00, 0x02, 0x00, 0x5f, 0x19, 0x32, 0x00, 0x00, 0x1e, 0x26, 0x04, 0x3e, 0x01, 0x00, 0x00, 0x17, 0x1a, 0x00, 0x00, 0x00, 0x20, 0x27, 0x0a, 0x83, 0x00, 0x00, 0x00, 0x5f, 0x19, 0x32, 0x00, 0x01, 0x7b, 0x27, 0x1f, 0x96, 0x00, 0x00, 0x00, 0x17, 0x1a, 0x00, 0x00, 0x01, 0x7f, 0x1f, 0x14, 0x7d, 0x00, 0x00, 0x00, 0x07, 0x1a, 0x00, 0x00, 0x01, 0x80, 0x00, 0x02, 0x66, 0x00, 0x00, 0x00, 0x00, 0x12, 0x00, 0x00, 0x01, 0x88, 0x29, 0x23, 0xb9, 0x00, 0x00, 0x00, 0x17, 0x1a, 0x00, 0x00, 0x02, 0x01, 0x2c, 0x2f, 0xec, 0x00, 0x05, 0x00, 0x5f, 0x19, 0x32, 0x00, 0x02, 0x03, 0x25, 0x07, 0x1b, 0x00, 0x00, 0x00, 0x17, 0x19, 0x00, 0x00, 0x02, 0x07, 0x26, 0x10, 0x7f, 0x00, 0xe1, 0xff, 0x1f, 0x19, 0x00, 0x00, 0x02, 0x08, 0x29, 0x17, 0x49, 0x00, 0xff, 0xff, 0x5f, 0x19, 0x32, 0x00, 0x02, 0x0d, 0x2a, 0x27, 0x43, 0x00, 0x0b, 0x00, 0x5f, 0x19, 0x32, 0x00, 0x02, 0x15, 0x26, 0x14, 0xbb, 0x00, 0xfb, 0xff, 0x5f, 0x19, 0x32, 0x00, 0x02, 0x1a, 0x2d, 0x4d, 0x39, 0x01, 0x02, 0x00, 0x5f, 0x19, 0x32, 0x00, 0x02, 0x1f, 0x2a, 0x1e, 0x35, 0x01, 0x07, 0x00, 0x5f, 0x19, 0x32, 0x00, 0x02, 0x21, 0x28, 0x1e, 0x08, 0x01, 0x01, 0x00, 0x5f, 0x19, 0x32, 0x00, 0x03, 0x02, 0x00, 0x02, 0x64, 0x00, 0x00, 0x00, 0x10, 0x12, 0x00, 0x00, 0x03, 0x05, 0x00, 0x12, 0x78, 0x00, 0x00, 0x00, 0x10, 0x12, 0x00, 0x00, 0x03, 0x08, 0x20, 0x03, 0x2e, 0x00, 0x00, 0x00, 0x17, 0x1a, 0x00, 0x00, 0x03, 0x0d, 0x25, 0x0e, 0x31, 0x00, 0x07, 0x00, 0x5f, 0x19, 0x32, 0x00, 0x03, 0x13, 0x00, 0x07, 0xb6, 0x00, 0x00, 0x00, 0x10, 0x12, 0x00, 0x00, 0x03, 0x14, 0x2d, 0x28, 0x8f, 0x00, 0xf7, 0xff, 0x1f, 0x19, 0x00, 0x00, 0x03, 0x18, 0x00, 0x01, 0x55, 0x01, 0x00, 0x00, 0x10, 0x12, 0x00, 0x00, 0x03, 0x1a, 0x00, 0x13, 0x2c, 0x01, 0x00, 0x00, 0x10, 0x12, 0x00, 0x00, 0x03, 0x1d, 0x2f, 0x4c, 0x3f, 0x01, 0x03, 0x00, 0x5f, 0x19, 0x32, 0x00, 0x03, 0x1e, 0x2d, 0x2a, 0x60, 0x00, 0xfd, 0xff, 0x5f, 0x19, 0x32, 0x00, 0x03, 0x20, 0x2d, 0x27, 0x43, 0x00, 0x04, 0x00, 0x5f, 0x19, 0x32, 0x00, 0x03, 0x23, 0x27, 0x16, 0x20, 0x01, 0x00, 0x00, 0x27, 0x1a, 0x00, 0x00, 0x03, 0x27, 0x00, 0x03, 0x43, 0x00, 0x00, 0x00, 0x10, 0x12, 0x00, 0x00, 0x03, 0x29, 0x00, 0x04, 0x1c, 0x00, 0x00, 0x00, 0x10, 0x19, 0x00, 0x00, 0x03, 0x2d, 0x28, 0x14, 0xf5, 0x00, 0xf9, 0xff, 0x1f, 0x19, 0x00, 0x00, 0x03, 0x3c, 0x00, 0x04, 0x67, 0x00, 0x00, 0x00, 0x10, 0x12, 0x00, 0x00, 0x05, 0x03, 0x00, 0xa5, 0x00, 0x00, 0x00, 0x00, 0x01, 0x00, 0x00, 0x00, 0x06, 0x01, 0x26, 0x15, 0x99, 0x00, 0xea, 0xff, 0x5f, 0x19, 0x32, 0x00, 0x06, 0x07, 0x2b, 0x1b, 0x24, 0x00, 0xf6, 0xff, 0x5f, 0x19, 0x32, 0x00, 0x06, 0x08, 0x2d, 0x2c, 0x5f, 0x00, 0xeb, 0xff, 0x5f, 0x19, 0x32, 0x00, 0x06, 0x0d, 0x1c, 0x0b, 0xd4, 0x00, 0xe1, 0xff, 0x5f, 0x19, 0x12, 0x00, 0x06, 0x0e, 0x2a, 0x24, 0x0c, 0x01, 0xdf, 0xff, 0x5f, 0x19, 0x32, 0x00, 0x06, 0x0f, 0x2a, 0x16, 0x47, 0x01, 0x06, 0x00, 0x1f, 0x19, 0x00, 0x00, 0x06, 0x11, 0x24, 0x06, 0x19, 0x01, 0x00, 0x00, 0x17, 0x1a, 0x00, 0x00, 0x06, 0x16, 0x27, 0x07, 0x55, 0x00, 0x00, 0x00, 0x17, 0x19, 0x00, 0x00, 0x06, 0x17, 0x2b, 0x38, 0x32, 0x00, 0xf8, 0xff, 0x5f, 0x19, 0x32, 0x00, 0x06, 0x18, 0x2e, 0x34, 0x34, 0x01, 0x06, 0x00, 0x5f, 0x19, 0x32, 0x00, 0x46, 0x49 } }, + { "UBX-NAV-SIG", { 0xb5, 0x62, 0x01, 0x43, 0x38, 0x05, 0xb8, 0xfa, 0x43, 0x13, 0x00, 0x53, 0x00, 0x00, 0x00, 0x01, 0x00, 0x00, 0xf2, 0xff, 0x27, 0x07, 0x00, 0x00, 0x01, 0x00, 0x01, 0x00, 0x00, 0x00, 0x00, 0x01, 0x03, 0x00, 0xf7, 0xff, 0x24, 0x07, 0x00, 0x00, 0x01, 0x00, 0x01, 0x00, 0x00, 0x00, 0x00, 0x07, 0x00, 0x00, 0x00, 0x00, 0x1a, 0x07, 0x00, 0x00, 0x01, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x07, 0x03, 0x00, 0x00, 0x00, 0x16, 0x04, 0x00, 0x00, 0x01, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x08, 0x00, 0x00, 0x02, 0x00, 0x2e, 0x07, 0x04, 0x00, 0xf9, 0x00, 0x01, 0x00, 0x00, 0x00, 0x00, 0x08, 0x03, 0x00, 0x03, 0x00, 0x2c, 0x07, 0x04, 0x00, 0xf9, 0x00, 0x01, 0x00, 0x00, 0x00, 0x00, 0x0a, 0x00, 0x00, 0x05, 0x00, 0x31, 0x07, 0x04, 0x00, 0xf9, 0x00, 0x01, 0x00, 0x00, 0x00, 0x00, 0x0a, 0x03, 0x00, 0xff, 0xff, 0x2b, 0x07, 0x04, 0x00, 0xf9, 0x00, 0x01, 0x00, 0x00, 0x00, 0x00, 0x0f, 0x00, 0x00, 0x00, 0x00, 0x00, 0x01, 0x00, 0x00, 0x01, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x0f, 0x04, 0x00, 0x00, 0x00, 0x00, 0x01, 0x00, 0x00, 0x01, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x10, 0x00, 0x00, 0xfa, 0xff, 0x29, 0x07, 0x04, 0x00, 0xf9, 0x00, 0x01, 0x00, 0x00, 0x00, 0x00, 0x10, 0x04, 0x00, 0x00, 0x00, 0x00, 0x01, 0x00, 0x00, 0x01, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x12, 0x03, 0x00, 0xe9, 0xff, 0x24, 0x07, 0x00, 0x00, 0x01, 0x00, 0x01, 0x00, 0x00, 0x00, 0x00, 0x12, 0x00, 0x00, 0xec, 0xff, 0x29, 0x07, 0x00, 0x00, 0x01, 0x00, 0x01, 0x00, 0x00, 0x00, 0x00, 0x15, 0x00, 0x00, 0xfd, 0xff, 0x2b, 0x07, 0x04, 0x00, 0xf9, 0x00, 0x01, 0x00, 0x00, 0x00, 0x00, 0x15, 0x04, 0x00, 0x00, 0x00, 0x00, 0x01, 0x00, 0x00, 0x01, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x17, 0x00, 0x00, 0xfa, 0xff, 0x2c, 0x07, 0x04, 0x00, 0xf9, 0x00, 0x01, 0x00, 0x00, 0x00, 0x00, 0x17, 0x03, 0x00, 0xfa, 0xff, 0x2a, 0x07, 0x04, 0x00, 0xf9, 0x00, 0x01, 0x00, 0x00, 0x00, 0x00, 0x1a, 0x00, 0x00, 0x00, 0x00, 0x09, 0x03, 0x00, 0x00, 0x01, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x1a, 0x03, 0x00, 0x00, 0x00, 0x0f, 0x04, 0x00, 0x00, 0x01, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x1b, 0x00, 0x00, 0x02, 0x00, 0x2f, 0x07, 0x04, 0x00, 0xf9, 0x00, 0x01, 0x00, 0x00, 0x00, 0x00, 0x1b, 0x03, 0x00, 0x01, 0x00, 0x2b, 0x07, 0x04, 0x00, 0xe9, 0x00, 0x01, 0x00, 0x00, 0x00, 0x00, 0x1e, 0x00, 0x00, 0x00, 0x00, 0x26, 0x07, 0x00, 0x00, 0x01, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x1e, 0x03, 0x00, 0x00, 0x00, 0x20, 0x07, 0x00, 0x00, 0x01, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x20, 0x00, 0x00, 0x00, 0x00, 0x27, 0x07, 0x04, 0x00, 0xf9, 0x00, 0x01, 0x00, 0x00, 0x00, 0x00, 0x20, 0x03, 0x00, 0x08, 0x00, 0x24, 0x07, 0x04, 0x00, 0xf9, 0x00, 0x01, 0x00, 0x00, 0x00, 0x01, 0x7b, 0x00, 0x00, 0x00, 0x00, 0x27, 0x07, 0x00, 0x00, 0x01, 0x00, 0x00, 0x00, 0x00, 0x00, 0x01, 0x7f, 0x00, 0x00, 0x00, 0x00, 0x1f, 0x07, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x01, 0x88, 0x00, 0x00, 0x00, 0x00, 0x29, 0x07, 0x00, 0x00, 0x01, 0x00, 0x00, 0x00, 0x00, 0x00, 0x02, 0x01, 0x00, 0x00, 0x05, 0x00, 0x2c, 0x07, 0x04, 0x00, 0xf9, 0x00, 0x01, 0x00, 0x00, 0x00, 0x02, 0x01, 0x06, 0x00, 0x04, 0x00, 0x2f, 0x07, 0x04, 0x00, 0xf9, 0x00, 0x01, 0x00, 0x00, 0x00, 0x02, 0x03, 0x00, 0x00, 0x00, 0x00, 0x25, 0x07, 0x00, 0x00, 0x01, 0x00, 0x00, 0x00, 0x00, 0x00, 0x02, 0x03, 0x06, 0x00, 0x00, 0x00, 0x27, 0x07, 0x00, 0x00, 0x01, 0x00, 0x00, 0x00, 0x00, 0x00, 0x02, 0x07, 0x00, 0x00, 0xe1, 0xff, 0x26, 0x07, 0x00, 0x02, 0x21, 0x00, 0x01, 0x00, 0x00, 0x00, 0x02, 0x07, 0x06, 0x00, 0xd1, 0xff, 0x2a, 0x07, 0x00, 0x02, 0x21, 0x00, 0x01, 0x00, 0x00, 0x00, 0x02, 0x08, 0x00, 0x00, 0xff, 0xff, 0x29, 0x07, 0x04, 0x00, 0xf9, 0x00, 0x01, 0x00, 0x00, 0x00, 0x02, 0x08, 0x06, 0x00, 0xfe, 0xff, 0x2a, 0x07, 0x04, 0x00, 0xf9, 0x00, 0x01, 0x00, 0x00, 0x00, 0x02, 0x0d, 0x00, 0x00, 0x0b, 0x00, 0x2a, 0x07, 0x04, 0x00, 0xf9, 0x00, 0x01, 0x00, 0x00, 0x00, 0x02, 0x0d, 0x06, 0x00, 0x02, 0x00, 0x30, 0x07, 0x04, 0x00, 0xf9, 0x00, 0x01, 0x00, 0x00, 0x00, 0x02, 0x15, 0x00, 0x00, 0xfb, 0xff, 0x26, 0x07, 0x04, 0x00, 0xf9, 0x00, 0x01, 0x00, 0x00, 0x00, 0x02, 0x15, 0x06, 0x00, 0x01, 0x00, 0x29, 0x07, 0x04, 0x00, 0xf9, 0x00, 0x01, 0x00, 0x00, 0x00, 0x02, 0x1a, 0x06, 0x00, 0x01, 0x00, 0x31, 0x07, 0x04, 0x00, 0xf9, 0x00, 0x01, 0x00, 0x00, 0x00, 0x02, 0x1a, 0x00, 0x00, 0x02, 0x00, 0x2d, 0x07, 0x04, 0x00, 0xf9, 0x00, 0x01, 0x00, 0x00, 0x00, 0x02, 0x1f, 0x00, 0x00, 0x07, 0x00, 0x2a, 0x07, 0x04, 0x00, 0xf9, 0x00, 0x01, 0x00, 0x00, 0x00, 0x02, 0x1f, 0x06, 0x00, 0x02, 0x00, 0x2e, 0x07, 0x04, 0x00, 0xf9, 0x00, 0x01, 0x00, 0x00, 0x00, 0x02, 0x21, 0x00, 0x00, 0x01, 0x00, 0x28, 0x07, 0x04, 0x00, 0xf9, 0x00, 0x01, 0x00, 0x00, 0x00, 0x02, 0x21, 0x06, 0x00, 0x0a, 0x00, 0x2f, 0x07, 0x04, 0x00, 0xf9, 0x00, 0x01, 0x00, 0x00, 0x00, 0x03, 0x08, 0x00, 0x00, 0x00, 0x00, 0x20, 0x07, 0x00, 0x00, 0x01, 0x00, 0x00, 0x00, 0x00, 0x00, 0x03, 0x08, 0x02, 0x00, 0x00, 0x00, 0x24, 0x07, 0x00, 0x00, 0x01, 0x00, 0x00, 0x00, 0x00, 0x00, 0x03, 0x0d, 0x02, 0x00, 0x1c, 0x00, 0x28, 0x07, 0x04, 0x00, 0x69, 0x00, 0x01, 0x00, 0x00, 0x00, 0x03, 0x0d, 0x00, 0x00, 0x07, 0x00, 0x25, 0x07, 0x04, 0x00, 0xf9, 0x00, 0x01, 0x00, 0x00, 0x00, 0x03, 0x14, 0x00, 0x00, 0xf7, 0xff, 0x2d, 0x07, 0x00, 0x02, 0x21, 0x00, 0x01, 0x00, 0x00, 0x00, 0x03, 0x14, 0x02, 0x00, 0x00, 0x00, 0x00, 0x01, 0x00, 0x00, 0x01, 0x00, 0x00, 0x00, 0x00, 0x00, 0x03, 0x1a, 0x02, 0x00, 0x00, 0x00, 0x00, 0x01, 0x00, 0x00, 0x01, 0x00, 0x00, 0x00, 0x00, 0x00, 0x03, 0x1d, 0x00, 0x00, 0x03, 0x00, 0x2f, 0x07, 0x04, 0x00, 0xf9, 0x00, 0x01, 0x00, 0x00, 0x00, 0x03, 0x1d, 0x02, 0x00, 0x00, 0x00, 0x00, 0x01, 0x00, 0x00, 0x01, 0x00, 0x00, 0x00, 0x00, 0x00, 0x03, 0x1e, 0x00, 0x00, 0xfd, 0xff, 0x2d, 0x07, 0x04, 0x00, 0xf9, 0x00, 0x01, 0x00, 0x00, 0x00, 0x03, 0x1e, 0x02, 0x00, 0x00, 0x00, 0x00, 0x01, 0x00, 0x00, 0x01, 0x00, 0x00, 0x00, 0x00, 0x00, 0x03, 0x20, 0x00, 0x00, 0x04, 0x00, 0x2d, 0x07, 0x04, 0x00, 0xf9, 0x00, 0x01, 0x00, 0x00, 0x00, 0x03, 0x20, 0x02, 0x00, 0x00, 0x00, 0x00, 0x01, 0x00, 0x00, 0x01, 0x00, 0x00, 0x00, 0x00, 0x00, 0x03, 0x23, 0x00, 0x00, 0x00, 0x00, 0x27, 0x07, 0x00, 0x00, 0x02, 0x00, 0x00, 0x00, 0x00, 0x00, 0x03, 0x2d, 0x00, 0x00, 0xf9, 0xff, 0x28, 0x07, 0x00, 0x02, 0x21, 0x00, 0x01, 0x00, 0x00, 0x00, 0x03, 0x2d, 0x02, 0x00, 0x00, 0x00, 0x00, 0x01, 0x00, 0x00, 0x01, 0x00, 0x00, 0x00, 0x00, 0x00, 0x05, 0x03, 0x00, 0x00, 0x00, 0x00, 0x00, 0x01, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x06, 0x01, 0x00, 0x08, 0xea, 0xff, 0x26, 0x07, 0x04, 0x00, 0xf9, 0x00, 0x01, 0x00, 0x00, 0x00, 0x06, 0x01, 0x02, 0x08, 0x11, 0x00, 0x22, 0x07, 0x04, 0x00, 0x69, 0x00, 0x01, 0x00, 0x00, 0x00, 0x06, 0x07, 0x00, 0x0c, 0xf6, 0xff, 0x2b, 0x07, 0x04, 0x00, 0xf9, 0x00, 0x01, 0x00, 0x00, 0x00, 0x06, 0x07, 0x02, 0x0c, 0xf9, 0xff, 0x27, 0x07, 0x04, 0x00, 0xf9, 0x00, 0x01, 0x00, 0x00, 0x00, 0x06, 0x08, 0x00, 0x0d, 0xeb, 0xff, 0x2d, 0x07, 0x04, 0x00, 0xf9, 0x00, 0x01, 0x00, 0x00, 0x00, 0x06, 0x08, 0x02, 0x0d, 0xf3, 0xff, 0x2a, 0x07, 0x04, 0x00, 0xf9, 0x00, 0x01, 0x00, 0x00, 0x00, 0x06, 0x0d, 0x00, 0x05, 0xe1, 0xff, 0x1c, 0x07, 0x04, 0x00, 0x69, 0x00, 0x01, 0x00, 0x00, 0x00, 0x06, 0x0d, 0x02, 0x05, 0xf3, 0xff, 0x20, 0x07, 0x04, 0x00, 0xf9, 0x00, 0x01, 0x00, 0x00, 0x00, 0x06, 0x0e, 0x00, 0x00, 0xdf, 0xff, 0x2a, 0x07, 0x04, 0x00, 0xf9, 0x00, 0x01, 0x00, 0x00, 0x00, 0x06, 0x0e, 0x02, 0x00, 0xf5, 0xff, 0x2a, 0x07, 0x04, 0x00, 0xe9, 0x00, 0x01, 0x00, 0x00, 0x00, 0x06, 0x0f, 0x00, 0x07, 0x06, 0x00, 0x2a, 0x07, 0x00, 0x02, 0x21, 0x00, 0x01, 0x00, 0x00, 0x00, 0x06, 0x0f, 0x02, 0x07, 0x0d, 0x00, 0x29, 0x07, 0x00, 0x02, 0x21, 0x00, 0x01, 0x00, 0x00, 0x00, 0x06, 0x11, 0x00, 0x0b, 0x00, 0x00, 0x24, 0x07, 0x00, 0x00, 0x01, 0x00, 0x00, 0x00, 0x00, 0x00, 0x06, 0x16, 0x00, 0x04, 0x00, 0x00, 0x27, 0x07, 0x00, 0x00, 0x01, 0x00, 0x00, 0x00, 0x00, 0x00, 0x06, 0x16, 0x02, 0x04, 0x00, 0x00, 0x27, 0x07, 0x00, 0x00, 0x01, 0x00, 0x00, 0x00, 0x00, 0x00, 0x06, 0x17, 0x00, 0x0a, 0xf8, 0xff, 0x2b, 0x07, 0x04, 0x00, 0xf9, 0x00, 0x01, 0x00, 0x00, 0x00, 0x06, 0x17, 0x02, 0x0a, 0x00, 0x00, 0x00, 0x01, 0x00, 0x00, 0x01, 0x00, 0x00, 0x00, 0x00, 0x00, 0x06, 0x18, 0x00, 0x09, 0x06, 0x00, 0x2e, 0x07, 0x04, 0x00, 0xf9, 0x00, 0x01, 0x00, 0x00, 0x00, 0x06, 0x18, 0x02, 0x09, 0xf9, 0xff, 0x2c, 0x07, 0x04, 0x00, 0xf9, 0x00, 0x01, 0x00, 0x00, 0x00, 0xb0, 0xdd } }, + { "UBX-NAV-STATUS", { 0xb5, 0x62, 0x01, 0x03, 0x10, 0x00, 0xb8, 0xfa, 0x43, 0x13, 0x03, 0xdf, 0x03, 0x88, 0xf2, 0x13, 0x17, 0x00, 0xd5, 0x75, 0xb1, 0x00, 0xa0, 0x87 } }, + { "UBX-NAV-TIMEGPS", { 0xb5, 0x62, 0x01, 0x20, 0x10, 0x00, 0xb8, 0xfa, 0x43, 0x13, 0xb1, 0x41, 0x00, 0x00, 0xcd, 0x08, 0x12, 0x07, 0x01, 0x00, 0x00, 0x00, 0x1a, 0xa5 } }, + { "UBX-NAV-CLOCK", { 0xb5, 0x62, 0x01, 0x22, 0x14, 0x00, 0xb8, 0xfa, 0x43, 0x13, 0x8f, 0x00, 0x0f, 0x00, 0x0a, 0x01, 0x00, 0x00, 0x01, 0x00, 0x00, 0x00, 0x7d, 0x00, 0x00, 0x00, 0x66, 0x06 } }, + { "UBX-NAV-COV", { 0xb5, 0x62, 0x01, 0x36, 0x40, 0x00, 0xb8, 0xfa, 0x43, 0x13, 0x00, 0x01, 0x01, 0x00, 0x32, 0x30, 0x19, 0x40, 0x00, 0x00, 0x80, 0x3f, 0x2e, 0x8e, 0x69, 0x38, 0x88, 0x21, 0xad, 0xb6, 0x08, 0xd0, 0xf5, 0x37, 0x6d, 0x9e, 0x00, 0x38, 0x3b, 0xf0, 0xc3, 0xb5, 0x96, 0x61, 0x52, 0x39, 0xa9, 0x3c, 0x91, 0x3b, 0x58, 0x71, 0xe4, 0xb8, 0xb0, 0xc8, 0xb1, 0x39, 0x32, 0xfd, 0x05, 0x3b, 0x3c, 0xb1, 0x01, 0xb9, 0x3a, 0xe5, 0x8f, 0x3b, 0x47, 0x29 } }, + { "UBX-NAV-RELPOSNED", { 0xb5, 0x62, 0x01, 0x3c, 0x40, 0x00, 0x01, 0x00, 0x00, 0x00, 0xb8, 0xfa, 0x43, 0x13, 0xb8, 0xd6, 0x24, 0x00, 0x22, 0xb1, 0x09, 0x00, 0x85, 0x3a, 0x00, 0x00, 0xd1, 0x17, 0x26, 0x00, 0xcd, 0x7d, 0x16, 0x00, 0x00, 0x00, 0x00, 0x00, 0x4e, 0x4e, 0x40, 0x3b, 0x64, 0x00, 0x00, 0x00, 0x64, 0x00, 0x00, 0x00, 0x8e, 0x00, 0x00, 0x00, 0x64, 0x00, 0x00, 0x00, 0x02, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x17, 0x01, 0x00, 0x00, 0x2c, 0x10 } }, + { "UBX-NAV-EOE", { 0xb5, 0x62, 0x01, 0x61, 0x04, 0x00, 0xb8, 0xfa, 0x43, 0x13, 0x6e, 0x2e } }, + }, { + })); // clang-format on + + // Exercise parser detector function + TestDetector({ 0xb5, 0x62, 0x01, 0x61, 0x04, 0x00, 0xb8, 0xfa, 0x43, 0x13, 0x6e, 0x2e }); + TestBadMessage({ 0xb6, 0x62, 0x01, 0x61, 0x04, 0x00, 0xb8, 0xfa, 0x43, 0x13, 0x6e, 0x2e }); // bad sync char + TestBadMessage({ 0xb5, 0x63, 0x01, 0x61, 0x04, 0x00, 0xb8, 0xfa, 0x43, 0x13, 0x6e, 0x2e }); // bad sync char + TestBadMessage({ 0xb5, 0x62, 0x01, 0x61, 0xff, 0xff, 0xb8, 0xfa, 0x43, 0x13, 0x6e, 0x2e }); // too long payload + TestBadMessage({ 0xb5, 0x62, 0x01, 0x61, 0x04, 0x00, 0xb8, 0xfa, 0x43, 0x13, 0x6f, 0x2e }); // bad crc + TestBadMessage({ 0xb5, 0x62, 0x01, 0x61, 0x04, 0x00, 0xb8, 0xfa, 0x43, 0x13, 0x6e, 0x2f }); // bad crc +} + +// --------------------------------------------------------------------------------------------------------------------- + +TEST_F(ParserTest, NOV_B) +{ + Parser parser; + EXPECT_TRUE( // clang-format off + TestLog(parser, TEST_DATA_NOVB_BIN, { + { "NOV_B-BESTPOS", { 0xaa, 0x44, 0x12, 0x1c, 0x2a, 0x00, 0x00, 0xa0, 0x48, 0x00, 0x00, 0x00, 0x23, 0xb4, 0x83, 0x08, 0x64, 0xdb, 0x68, 0x0c, 0x00, 0x08, 0x00, 0x03, 0xba, 0xcd, 0x19, 0x40, 0x00, 0x00, 0x00, 0x00, 0x38, 0x00, 0x00, 0x00, 0xcf, 0x6a, 0x48, 0x15, 0x4c, 0xb3, 0x47, 0x40, 0xe6, 0xeb, 0x19, 0x6b, 0xb8, 0xe3, 0x20, 0x40, 0x00, 0x00, 0x58, 0x31, 0xd2, 0x84, 0x78, 0x40, 0x66, 0x66, 0x3e, 0x42, 0x3d, 0x00, 0x00, 0x00, 0x85, 0x2d, 0x11, 0x3d, 0xf3, 0xd6, 0x04, 0x3d, 0xc6, 0x57, 0x52, 0x3d, 0x30, 0x00, 0x00, 0x00, 0x00, 0x00, 0x80, 0x3f, 0x00, 0x00, 0x00, 0x00, 0x16, 0x15, 0x15, 0x10, 0x00, 0x21, 0x15, 0x33, 0x3f, 0x6c, 0xbc, 0xfe } }, + { "NOV_B-BESTXYZ", { 0xaa, 0x44, 0x12, 0x1c, 0xf1, 0x00, 0x00, 0xa0, 0x70, 0x00, 0x00, 0x00, 0x23, 0xb4, 0x83, 0x08, 0x64, 0xdb, 0x68, 0x0c, 0x00, 0x08, 0x00, 0x03, 0xcf, 0x44, 0x19, 0x40, 0x00, 0x00, 0x00, 0x00, 0x38, 0x00, 0x00, 0x00, 0x1f, 0x3d, 0xf8, 0xcb, 0x1f, 0x52, 0x50, 0x41, 0x78, 0xc3, 0x4c, 0x3a, 0x76, 0x62, 0x23, 0x41, 0x6f, 0x85, 0xb2, 0x17, 0xda, 0xd2, 0x51, 0x41, 0x16, 0x9c, 0x45, 0x3d, 0x33, 0x55, 0x00, 0x3d, 0xc7, 0xac, 0x25, 0x3d, 0x00, 0x00, 0x00, 0x00, 0x38, 0x00, 0x00, 0x00, 0x44, 0xe5, 0x5d, 0x83, 0x19, 0x93, 0x60, 0x3f, 0xf2, 0x70, 0xb0, 0x6b, 0xcf, 0xcd, 0x58, 0xbf, 0xa0, 0xee, 0x54, 0x82, 0xfd, 0xe1, 0x0c, 0xbf, 0x28, 0x7c, 0xe1, 0x3a, 0xca, 0x65, 0xe9, 0x3a, 0xf8, 0xae, 0xdf, 0x3a, 0x30, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x80, 0x3f, 0x00, 0x00, 0x00, 0x00, 0x16, 0x15, 0x15, 0x10, 0x00, 0x21, 0x15, 0x33, 0x0d, 0xdb, 0x0c, 0xcd } }, + { "NOV_B-RAWIMUSX", { 0xaa, 0x44, 0x13, 0x28, 0xb6, 0x05, 0x83, 0x08, 0x5b, 0xdb, 0x68, 0x0c, 0x04, 0x3d, 0x83, 0x08, 0x32, 0xac, 0xe2, 0xed, 0x33, 0x6a, 0x09, 0x41, 0x00, 0xfe, 0x27, 0xf8, 0x04, 0x11, 0xd5, 0x09, 0xbc, 0x60, 0x60, 0x00, 0x54, 0xfe, 0x61, 0x00, 0x94, 0x0d, 0x01, 0x00, 0xe0, 0x63, 0x08, 0x00, 0x9c, 0xf5, 0x02, 0x00, 0xea, 0xf1, 0x93, 0x8c } }, + }, { + })); // clang-format on + + TestDetector({ 0xaa, 0x44, 0x13, 0x28, 0xb6, 0x05, 0x83, 0x08, 0x5b, 0xdb, 0x68, 0x0c, 0x04, 0x3d, 0x83, 0x08, 0x32, + 0xac, 0xe2, 0xed, 0x33, 0x6a, 0x09, 0x41, 0x00, 0xfe, 0x27, 0xf8, 0x04, 0x11, 0xd5, 0x09, 0xbc, 0x60, 0x60, + 0x00, 0x54, 0xfe, 0x61, 0x00, 0x94, 0x0d, 0x01, 0x00, 0xe0, 0x63, 0x08, 0x00, 0x9c, 0xf5, 0x02, 0x00, 0xea, + 0xf1, 0x93, 0x8c }); + TestBadMessage({ 0xaa, 0x44, 0x12, 0x1c, 0x2a, 0x00, 0x00, 0xa0, 0xff, 0xff, 0x00, 0x00, 0x23, 0xb4, 0x83, 0x08, + 0x64, 0xdb, 0x68, 0x0c, 0x00, 0x08, 0x00, 0x03, 0xba, 0xcd, 0x19, 0x40, 0x00, 0x00, 0x00, 0x00, 0x38, 0x00, + 0x00, 0x00, 0xcf, 0x6a, 0x48, 0x15, 0x4c, 0xb3, 0x47, 0x40, 0xe6, 0xeb, 0x19, 0x6b, 0xb8, 0xe3, 0x20, 0x40, + 0x00, 0x00, 0x58, 0x31, 0xd2, 0x84, 0x78, 0x40, 0x66, 0x66, 0x3e, 0x42, 0x3d, 0x00, 0x00, 0x00, 0x85, 0x2d, + 0x11, 0x3d, 0xf3, 0xd6, 0x04, 0x3d, 0xc6, 0x57, 0x52, 0x3d, 0x30, 0x00, 0x00, 0x00, 0x00, 0x00, 0x80, 0x3f, + 0x00, 0x00, 0x00, 0x00, 0x16, 0x15, 0x15, 0x10, 0x00, 0x21, 0x15, 0x33, 0x3f, 0x6c, 0xbc, 0xfe }); // too long + TestBadMessage({ 0xaa, 0x44, 0x13, 0x28, 0xb6, 0x05, 0x83, 0x08, 0x5b, 0xdb, 0x68, 0x0c, 0x04, 0x3d, 0x83, 0x08, + 0x32, 0xac, 0xe2, 0xed, 0x33, 0x6a, 0x09, 0x41, 0x00, 0xfe, 0x27, 0xf8, 0x04, 0x11, 0xd5, 0x09, 0xbc, 0x60, + 0x60, 0x00, 0x54, 0xfe, 0x61, 0x00, 0x94, 0x0d, 0x01, 0x00, 0xe0, 0x63, 0x08, 0x00, 0x9c, 0xf5, 0x02, 0x00, + 0xea, 0xf1, 0x93, 0x8d }); // bad CRC +} + +// --------------------------------------------------------------------------------------------------------------------- + +TEST_F(ParserTest, RTCM3) +{ + Parser parser; + EXPECT_TRUE( // clang-format off + TestLog(parser, TEST_DATA_RTCM3_BIN, { + { "RTCM3-TYPE1107", { 0xd3, 0x00, 0x16, 0x45, 0x30, 0x00, 0x4d, 0x10, 0x93, 0xa2, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x1f, 0x9b, 0x2f } }, + { "RTCM3-TYPE1077", { 0xd3, 0x01, 0x21, 0x43, 0x50, 0x00, 0x4d, 0x10, 0x93, 0xa2, 0x00, 0x00, 0x40, 0xa1, 0xa5, 0x32, 0x80, 0x00, 0x00, 0x00, 0x20, 0x00, 0x80, 0x00, 0x7f, 0xdd, 0xfb, 0xa8, 0xa2, 0x22, 0xa9, 0xa5, 0xa9, 0x25, 0x24, 0xaa, 0x21, 0xaa, 0x29, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x6d, 0x39, 0xaa, 0xad, 0x7f, 0x4a, 0x28, 0x71, 0x1f, 0xd9, 0x2d, 0x00, 0x8f, 0x17, 0x06, 0x7d, 0x6e, 0x01, 0xa8, 0x2d, 0xe1, 0x7c, 0x07, 0x8c, 0x1d, 0x5f, 0xf5, 0x41, 0x8b, 0x07, 0xfe, 0x0f, 0x50, 0x35, 0xdf, 0x85, 0x0a, 0x14, 0xb8, 0xad, 0xe6, 0x6a, 0x5a, 0x7e, 0xa0, 0x41, 0xe2, 0xde, 0x76, 0x1c, 0xa0, 0x62, 0x70, 0x66, 0x16, 0x88, 0x1b, 0x9f, 0xce, 0xde, 0x14, 0xed, 0x6c, 0xbf, 0x60, 0x94, 0xf8, 0x0e, 0xdf, 0x6f, 0x44, 0xfe, 0x1c, 0x77, 0xb1, 0x3b, 0x7c, 0x27, 0xa7, 0xb2, 0xe8, 0x6e, 0x8c, 0x2e, 0x34, 0x19, 0x63, 0x69, 0x4f, 0xff, 0xf7, 0xa0, 0x9e, 0x2c, 0xcf, 0xfd, 0x4c, 0x07, 0x8f, 0xa6, 0x57, 0x61, 0x75, 0x77, 0x84, 0x20, 0xe0, 0x09, 0x5c, 0x3f, 0xff, 0xeb, 0x60, 0x4e, 0x05, 0x5f, 0xf8, 0x93, 0xaf, 0xa4, 0xe5, 0x28, 0x40, 0xa0, 0xa7, 0xa5, 0x52, 0xa0, 0x61, 0x07, 0x78, 0x00, 0x0f, 0x7f, 0xff, 0xf7, 0x50, 0x72, 0xa1, 0x50, 0x18, 0xbe, 0x67, 0xff, 0xf8, 0x37, 0x9f, 0xfc, 0x7f, 0x5b, 0x15, 0xd8, 0x00, 0xe0, 0xca, 0x32, 0xdc, 0xcf, 0x31, 0xc4, 0x80, 0x04, 0xed, 0x41, 0x50, 0xb0, 0xa4, 0xd7, 0x32, 0x00, 0x00, 0x04, 0xd3, 0x39, 0x00, 0x10, 0x33, 0x58, 0x00, 0x04, 0x47, 0xc2, 0x80, 0xbc, 0x2f, 0x0b, 0x82, 0x80, 0x94, 0x1f, 0x0b, 0x42, 0x40, 0x98, 0x2e, 0x0a, 0x82, 0x50, 0x50, 0x1c, 0x0b, 0x42, 0xa0, 0x44, 0x28, 0x09, 0x43, 0x82, 0xe7, 0x0c, 0x80, 0x94, 0x41, 0x38, 0x39, 0x80, 0x73, 0xc1, 0x11, 0x6a, 0x2f, 0x34, 0x7d, 0x87, 0xa5, 0x9e, 0xe6, 0x1f, 0x88, 0x36, 0xaf, 0x6a, 0x88, 0x05, 0x10, 0x63, 0xf4, 0x8c, 0x21, 0x57, 0x41, 0xc5, 0x1c, 0x8d, 0x36, 0xbd, 0x80, 0x91, 0xb2, 0x79 } }, + { "RTCM3-TYPE1033", { 0xd3, 0x00, 0x2e, 0x40, 0x90, 0x00, 0x0b, 0x4e, 0x55, 0x4c, 0x4c, 0x41, 0x4e, 0x54, 0x45, 0x4e, 0x4e, 0x41, 0x00, 0x00, 0x15, 0x52, 0x54, 0x4b, 0x42, 0x61, 0x73, 0x65, 0x20, 0x55, 0x62, 0x6c, 0x6f, 0x78, 0x5f, 0x5a, 0x45, 0x44, 0x2d, 0x46, 0x39, 0x50, 0x05, 0x32, 0x2e, 0x33, 0x2e, 0x30, 0x00, 0x7c, 0x92, 0xfb } }, + }, { + })); // clang-format on + + TestDetector({ 0xd3, 0x00, 0x16, 0x45, 0x30, 0x00, 0x4d, 0x10, 0x93, 0xa2, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x1f, 0x9b, 0x2f }); + TestBadMessage({ 0xd3, 0xff, 0xff, 0x45, 0x30, 0x00, 0x4d, 0x10, 0x93, 0xa2, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x1f, 0x9b, 0x2f }); // too long payload + TestBadMessage({ 0xd3, 0x00, 0x16, 0x45, 0x30, 0x00, 0x4d, 0x10, 0x93, 0xa2, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x1f, 0x9c, 0x2f }); // bad CRC +} + +// --------------------------------------------------------------------------------------------------------------------- + +TEST_F(ParserTest, SPARTN) +{ + Parser parser; + EXPECT_TRUE( // clang-format off + TestLog(parser, TEST_DATA_SPARTN_BIN, { + { "SPARTN-OCB-GLO", { 0x73, 0x00, 0x10, 0xe3, 0x18, 0xb9, 0xa1, 0x8d, 0x68, 0x5b, 0x1f, 0x88, 0xa0, 0xba, 0xc2, 0x37, 0x43, 0xeb, 0x3f, 0xbe, 0x08, 0xf8, 0x51, 0x7f, 0x3a, 0x9a, 0x78, 0x32, 0x85, 0xc6, 0xe2, 0xd0, 0x7e, 0xee, 0x37, 0xcb, 0x3d, 0x6a, 0x8f, 0xf1, 0x4c, 0x27, 0x43, 0x0d, 0x2a, 0x70, 0xf2, 0x01 } }, + { "SPARTN-OCB-GPS", { 0x73, 0x00, 0x7a, 0x6a, 0x08, 0xb9, 0xa0, 0x3d, 0xe0, 0x5b, 0x1d, 0x48, 0x92, 0x20, 0xe3, 0x57, 0xa1, 0x89, 0x26, 0x9b, 0xfe, 0x4c, 0x18, 0xf4, 0x14, 0x2e, 0x2c, 0xc1, 0x6c, 0x23, 0xa7, 0x0b, 0x66, 0xfc, 0xc0, 0xc9, 0xcb, 0xa7, 0xc0, 0x18, 0x82, 0xd5, 0x59, 0x4a, 0xda, 0x6e, 0xa3, 0x6b, 0x06, 0xd5, 0xa7, 0x00, 0xd5, 0xcd, 0xd3, 0xb8, 0x98, 0xbb, 0x37, 0x3c, 0x36, 0x6b, 0x13, 0x70, 0xf7, 0xd5, 0x46, 0x11, 0x00, 0x1e, 0xb1, 0x0d, 0x47, 0x1e, 0xcd, 0xdd, 0x8b, 0xb0, 0x40, 0xba, 0xb6, 0x86, 0x5c, 0x4c, 0x25, 0x62, 0xdd, 0xff, 0xdb, 0xee, 0x6c, 0x98, 0xe5, 0xd4, 0xae, 0xf6, 0xb8, 0x5e, 0xf3, 0x3e, 0x9f, 0xa0, 0x6c, 0x1b, 0xbd, 0xec, 0xbb, 0xea, 0x88, 0x34, 0xf3, 0x57, 0x33, 0x9a, 0x4a, 0x29, 0x70, 0x9f, 0x14, 0x99, 0x1d, 0x4f, 0x9e, 0xdd, 0x92, 0x48, 0x70, 0x24, 0x28, 0x5c, 0x1a, 0xb4, 0x65, 0x1c, 0x7d, 0x2f, 0x86, 0x31, 0xd3, 0x3f, 0xa6, 0xf6, 0xa0, 0x43, 0xb0, 0x0b, 0x5f, 0xcc, 0xad, 0xb4, 0xa0, 0xe8, 0xd9, 0xe1, 0x60, 0x19, 0x46, 0xe7, 0xbd, 0x64, 0x2f, 0x09, 0x1a, 0x82, 0xb6, 0x1f, 0x37, 0x20, 0x79, 0xde, 0x64, 0x60, 0x4a, 0x9f, 0x2e, 0x52, 0x6d, 0xa0, 0x20, 0x97, 0xab, 0xb6, 0xd2, 0x57, 0x44, 0xc7, 0xa4, 0xd1, 0x08, 0xf0, 0xd0, 0x3c, 0xe4, 0xc8, 0x9e, 0x75, 0x9a, 0x66, 0xea, 0xd8, 0x78, 0x24, 0x13, 0x7a, 0xd0, 0xd2, 0xab, 0x29, 0x1c, 0xaf, 0x2e, 0x37, 0x94, 0x3b, 0x58, 0x31, 0x58, 0x56, 0xe1, 0x04, 0x45, 0x99, 0x7a, 0xc6, 0x7f, 0x85, 0xe1, 0x91, 0x9a, 0x77, 0x85, 0x5b, 0x6b, 0x3d, 0x2f, 0x55, 0x8c, 0x59, 0xe7, 0x06, 0x7f, 0x32, 0xa4, 0x26, 0x44, 0xb7, 0x44, 0x10, 0x1d, 0xa5, 0xbb, 0xf4, 0x59, 0x00, 0xf6, 0x1b, 0x2a, 0x06, 0xc7 } }, + { "SPARTN-GAD-GAD", { 0x73, 0x04, 0x07, 0xe4, 0x01, 0x4c, 0xd0, 0x5b, 0x1e, 0x48, 0xfe, 0x92, 0xb2, 0xd6, 0xd1, 0xe6, 0x6f, 0x07, 0x30, 0x68, 0x18, 0x8e, 0x48, 0xb3, 0xe1, 0x26, 0x20, 0x4a } }, + { "SPARTN-HPAC-GLO", { 0x73, 0x02, 0x58, 0xea, 0x18, 0xb9, 0xa1, 0x8f, 0xc0, 0x5b, 0x19, 0x88, 0xda, 0x72, 0xd2, 0x47, 0xb4, 0xf6, 0x0b, 0x58, 0x9a, 0x57, 0x9e, 0x28, 0xb3, 0x29, 0x13, 0xdd, 0xad, 0x03, 0x18, 0x80, 0xbe, 0xdf, 0xcd, 0x67, 0xf9, 0xae, 0x17, 0xbe, 0x9c, 0x53, 0x38, 0xed, 0x41, 0xf0, 0xc2, 0xd7, 0xca, 0x77, 0x31, 0x3d, 0xad, 0xa2, 0xb5, 0x18, 0x53, 0x64, 0xa4, 0xc1, 0xf0, 0x16, 0x53, 0xa5, 0x1e, 0x76, 0xa9, 0x37, 0x97, 0x52, 0x54, 0x47, 0xed, 0x41, 0x73, 0xe1, 0x70, 0x63, 0x89, 0x30, 0x29, 0x77, 0x1a, 0x39, 0x9d, 0x01, 0xb2, 0x02, 0x65, 0x6f, 0x4b, 0x75, 0x6f, 0x01, 0x01, 0xf0, 0x21, 0x5a, 0x4e, 0xc6, 0x2d, 0x2a, 0xa3, 0x9f, 0x3a, 0x08, 0x03, 0x93, 0x2d, 0x1e, 0x82, 0x94, 0xe9, 0x67, 0xb3, 0xdb, 0xd7, 0x7e, 0xbd, 0x49, 0x5a, 0x46, 0xe5, 0x03, 0xe8, 0x9e, 0x7a, 0xee, 0xba, 0x78, 0x6c, 0x12, 0x71, 0xb1, 0xf7, 0xc7, 0xfb, 0xc5, 0x65, 0xa7, 0xa8, 0x83, 0xf8, 0xb9, 0x9b, 0x83, 0x08, 0x29, 0xe6, 0x84, 0xf5, 0x6f, 0x8d, 0xb2, 0x01, 0x74, 0xed, 0x27, 0xc7, 0x57, 0xc9, 0x41, 0x63, 0x8e, 0xb5, 0x7c, 0x6f, 0xfa, 0x1f, 0xfa, 0xee, 0xfc, 0x17, 0xf9, 0x9b, 0x60, 0xa4, 0x16, 0x6c, 0xa1, 0x3e, 0xb7, 0xe2, 0x16, 0xc6, 0xd7, 0x24, 0xd2, 0x06, 0xc6, 0x9a, 0xb2 } }, + }, { + })); // clang-format on + + TestDetector({ 0x73, 0x02, 0x58, 0xea, 0x18, 0xb9, 0xa1, 0x8f, 0xc0, 0x5b, 0x19, 0x88, 0xda, 0x72, 0xd2, 0x47, 0xb4, + 0xf6, 0x0b, 0x58, 0x9a, 0x57, 0x9e, 0x28, 0xb3, 0x29, 0x13, 0xdd, 0xad, 0x03, 0x18, 0x80, 0xbe, 0xdf, 0xcd, + 0x67, 0xf9, 0xae, 0x17, 0xbe, 0x9c, 0x53, 0x38, 0xed, 0x41, 0xf0, 0xc2, 0xd7, 0xca, 0x77, 0x31, 0x3d, 0xad, + 0xa2, 0xb5, 0x18, 0x53, 0x64, 0xa4, 0xc1, 0xf0, 0x16, 0x53, 0xa5, 0x1e, 0x76, 0xa9, 0x37, 0x97, 0x52, 0x54, + 0x47, 0xed, 0x41, 0x73, 0xe1, 0x70, 0x63, 0x89, 0x30, 0x29, 0x77, 0x1a, 0x39, 0x9d, 0x01, 0xb2, 0x02, 0x65, + 0x6f, 0x4b, 0x75, 0x6f, 0x01, 0x01, 0xf0, 0x21, 0x5a, 0x4e, 0xc6, 0x2d, 0x2a, 0xa3, 0x9f, 0x3a, 0x08, 0x03, + 0x93, 0x2d, 0x1e, 0x82, 0x94, 0xe9, 0x67, 0xb3, 0xdb, 0xd7, 0x7e, 0xbd, 0x49, 0x5a, 0x46, 0xe5, 0x03, 0xe8, + 0x9e, 0x7a, 0xee, 0xba, 0x78, 0x6c, 0x12, 0x71, 0xb1, 0xf7, 0xc7, 0xfb, 0xc5, 0x65, 0xa7, 0xa8, 0x83, 0xf8, + 0xb9, 0x9b, 0x83, 0x08, 0x29, 0xe6, 0x84, 0xf5, 0x6f, 0x8d, 0xb2, 0x01, 0x74, 0xed, 0x27, 0xc7, 0x57, 0xc9, + 0x41, 0x63, 0x8e, 0xb5, 0x7c, 0x6f, 0xfa, 0x1f, 0xfa, 0xee, 0xfc, 0x17, 0xf9, 0x9b, 0x60, 0xa4, 0x16, 0x6c, + 0xa1, 0x3e, 0xb7, 0xe2, 0x16, 0xc6, 0xd7, 0x24, 0xd2, 0x06, 0xc6, 0x9a, 0xb2 }); + TestBadMessage({ 0x73, 0x04, 0x07, 0xe4, 0x01, 0x4c, 0xd0, 0x5b, 0x1e, 0x48, 0xfe, 0x92, 0xb2, 0xd6, 0xd1, 0xe6, + 0x6f, 0x07, 0x30, 0x68, 0x18, 0x8e, 0x48, 0xb3, 0xe1, 0x26, 0x20, 0x4b }); // bad CRC +} + +// --------------------------------------------------------------------------------------------------------------------- + +TEST_F(ParserTest, FP_A) +{ + Parser parser; + EXPECT_TRUE( // clang-format off + TestLog(parser, TEST_DATA_FPA_BIN, { + { "FP_A-ODOMETRY", { 0x24, 0x46, 0x50, 0x2c, 0x4f, 0x44, 0x4f, 0x4d, 0x45, 0x54, 0x52, 0x59, 0x2c, 0x32, 0x2c, 0x32, 0x32, 0x35, 0x33, 0x2c, 0x33, 0x32, 0x33, 0x32, 0x39, 0x39, 0x2e, 0x31, 0x30, 0x30, 0x30, 0x30, 0x30, 0x2c, 0x2c, 0x2c, 0x2c, 0x2c, 0x2c, 0x2c, 0x2c, 0x2c, 0x2c, 0x2c, 0x2c, 0x2c, 0x2c, 0x2c, 0x2c, 0x2c, 0x30, 0x2c, 0x30, 0x2c, 0x38, 0x2c, 0x38, 0x2c, 0x2d, 0x31, 0x2c, 0x2c, 0x2c, 0x2c, 0x2c, 0x2c, 0x2c, 0x2c, 0x2c, 0x2c, 0x2c, 0x2c, 0x2c, 0x2c, 0x2c, 0x2c, 0x2c, 0x2c, 0x2c, 0x66, 0x70, 0x5f, 0x72, 0x65, 0x6c, 0x65, 0x61, 0x73, 0x65, 0x5f, 0x76, 0x72, 0x32, 0x5f, 0x32, 0x2e, 0x36, 0x33, 0x2e, 0x31, 0x5f, 0x32, 0x30, 0x34, 0x2a, 0x37, 0x42, 0x0d, 0x0a } }, + { "FP_A-TF", { 0x24, 0x46, 0x50, 0x2c, 0x54, 0x46, 0x2c, 0x32, 0x2c, 0x32, 0x32, 0x35, 0x33, 0x2c, 0x33, 0x32, 0x33, 0x32, 0x39, 0x39, 0x2e, 0x30, 0x30, 0x30, 0x30, 0x30, 0x30, 0x2c, 0x56, 0x52, 0x54, 0x4b, 0x2c, 0x43, 0x41, 0x4d, 0x2c, 0x2d, 0x30, 0x2e, 0x30, 0x33, 0x34, 0x30, 0x30, 0x2c, 0x30, 0x2e, 0x30, 0x30, 0x32, 0x30, 0x30, 0x2c, 0x2d, 0x30, 0x2e, 0x30, 0x31, 0x36, 0x30, 0x30, 0x2c, 0x2d, 0x30, 0x2e, 0x30, 0x30, 0x30, 0x30, 0x30, 0x30, 0x2c, 0x30, 0x2e, 0x30, 0x30, 0x30, 0x30, 0x30, 0x30, 0x2c, 0x30, 0x2e, 0x30, 0x30, 0x30, 0x30, 0x30, 0x30, 0x2c, 0x31, 0x2e, 0x30, 0x30, 0x30, 0x30, 0x30, 0x30, 0x2a, 0x36, 0x36, 0x0d, 0x0a } }, + }, { + })); // clang-format on +} + +// --------------------------------------------------------------------------------------------------------------------- + +TEST_F(ParserTest, NMEA) +{ + Parser parser; + EXPECT_TRUE( // clang-format off + TestLog(parser, TEST_DATA_NMEA_BIN, { + { "NMEA-GN-RMC", { 0x24, 0x47, 0x4e, 0x52, 0x4d, 0x43, 0x2c, 0x31, 0x37, 0x34, 0x36, 0x34, 0x34, 0x2e, 0x32, 0x30, 0x2c, 0x41, 0x2c, 0x34, 0x37, 0x32, 0x34, 0x2e, 0x30, 0x31, 0x38, 0x31, 0x38, 0x2c, 0x4e, 0x2c, 0x30, 0x30, 0x38, 0x32, 0x37, 0x2e, 0x30, 0x32, 0x32, 0x34, 0x34, 0x2c, 0x45, 0x2c, 0x30, 0x2e, 0x30, 0x31, 0x33, 0x2c, 0x2c, 0x31, 0x35, 0x30, 0x33, 0x32, 0x33, 0x2c, 0x2c, 0x2c, 0x52, 0x2c, 0x56, 0x2a, 0x30, 0x44, 0x0d, 0x0a } }, + { "NMEA-GN-GGA", { 0x24, 0x47, 0x4e, 0x47, 0x47, 0x41, 0x2c, 0x31, 0x37, 0x34, 0x36, 0x34, 0x34, 0x2e, 0x32, 0x30, 0x2c, 0x34, 0x37, 0x32, 0x34, 0x2e, 0x30, 0x31, 0x38, 0x31, 0x38, 0x2c, 0x4e, 0x2c, 0x30, 0x30, 0x38, 0x32, 0x37, 0x2e, 0x30, 0x32, 0x32, 0x34, 0x34, 0x2c, 0x45, 0x2c, 0x34, 0x2c, 0x31, 0x32, 0x2c, 0x30, 0x2e, 0x35, 0x38, 0x2c, 0x34, 0x31, 0x32, 0x2e, 0x31, 0x2c, 0x4d, 0x2c, 0x34, 0x37, 0x2e, 0x33, 0x2c, 0x4d, 0x2c, 0x31, 0x2e, 0x32, 0x2c, 0x30, 0x30, 0x30, 0x30, 0x2a, 0x36, 0x43, 0x0d, 0x0a } }, + }, { + })); // clang-format on + + TestDetector({ 0x24, 0x47, 0x4e, 0x52, 0x4d, 0x43, 0x2c, 0x31, 0x37, 0x34, 0x36, 0x34, 0x34, 0x2e, 0x32, 0x30, 0x2c, + 0x41, 0x2c, 0x34, 0x37, 0x32, 0x34, 0x2e, 0x30, 0x31, 0x38, 0x31, 0x38, 0x2c, 0x4e, 0x2c, 0x30, 0x30, 0x38, + 0x32, 0x37, 0x2e, 0x30, 0x32, 0x32, 0x34, 0x34, 0x2c, 0x45, 0x2c, 0x30, 0x2e, 0x30, 0x31, 0x33, 0x2c, 0x2c, + 0x31, 0x35, 0x30, 0x33, 0x32, 0x33, 0x2c, 0x2c, 0x2c, 0x52, 0x2c, 0x56, 0x2a, 0x30, 0x44, 0x0d, 0x0a }); + TestBadMessage({ 0x24, 0x47, 0x4e, 0x52, 0x4d, 0x43, 0x2c, 0x31, 0x37, 0x34, 0x36, 0x34, 0x34, 0x2e, 0x32, 0x30, + 0x2c, 0x41, 0x2c, 0x34, 0x37, 0x32, 0x34, 0x2e, 0x30, 0x31, 0x38, 0x31, 0x38, 0x2c, 0x4e, 0x2c, 0x30, 0x30, + 0x38, 0x32, 0x37, 0x2e, 0x30, 0x32, 0x32, '\\', // <-- here + 0x34, 0x2c, 0x45, 0x2c, 0x30, 0x2e, 0x30, 0x31, 0x33, 0x2c, 0x2c, 0x31, 0x35, 0x30, 0x33, 0x32, 0x33, 0x2c, + 0x2c, 0x2c, 0x52, 0x2c, 0x56, 0x2a, 0x30, 0x44, 0x0d, 0x0a }); // bad char + TestBadMessage({ 0x24, 0x47, 0x4e, 0x52, 0x4d, 0x43, 0x2c, 0x31, 0x37, 0x34, 0x36, 0x34, 0x34, 0x2e, 0x32, 0x30, + 0x2c, 0x41, 0x2c, 0x34, 0x37, 0x32, 0x34, 0x2e, 0x30, 0x31, 0x38, 0x31, 0x38, 0x2c, 0x4e, 0x2c, 0x30, 0x30, + 0x38, 0x32, 0x37, 0x2e, 0x30, 0x32, 0x32, '~', // <-- here + 0x34, 0x2c, 0x45, 0x2c, 0x30, 0x2e, 0x30, 0x31, 0x33, 0x2c, 0x2c, 0x31, 0x35, 0x30, 0x33, 0x32, 0x33, 0x2c, + 0x2c, 0x2c, 0x52, 0x2c, 0x56, 0x2a, 0x30, 0x44, 0x0d, 0x0a }); // bad char + TestBadMessage({ 0x24, 0x47, 0x4e, 0x52, 0x4d, 0x43, 0x2c, 0x31, 0x37, 0x34, 0x36, 0x34, 0x34, 0x2e, 0x32, 0x30, + 0x2c, 0x41, 0x2c, 0x34, 0x37, 0x32, 0x34, 0x2e, 0x30, 0x31, 0x38, 0x31, 0x38, 0x2c, 0x4e, 0x2c, 0x30, 0x30, + 0x38, 0x32, 0x37, 0x2e, 0x30, 0x32, 0x32, '!', // <-- here + 0x34, 0x2c, 0x45, 0x2c, 0x30, 0x2e, 0x30, 0x31, 0x33, 0x2c, 0x2c, 0x31, 0x35, 0x30, 0x33, 0x32, 0x33, 0x2c, + 0x2c, 0x2c, 0x52, 0x2c, 0x56, 0x2a, 0x30, 0x44, 0x0d, 0x0a }); // bad char + TestBadMessage({ 0x24, 0x47, 0x4e, 0x52, 0x4d, 0x43, 0x2c, 0x31, 0x37, 0x34, 0x36, 0x34, 0x34, 0x2e, 0x32, 0x30, + 0x2c, 0x41, 0x2c, 0x34, 0x37, 0x32, 0x34, 0x2e, 0x30, 0x31, 0x38, 0x31, 0x38, 0x2c, 0x4e, 0x2c, 0x30, 0x30, + 0x38, 0x32, 0x37, 0x2e, 0x30, 0x32, 0x32, '$', // <-- here + 0x34, 0x2c, 0x45, 0x2c, 0x30, 0x2e, 0x30, 0x31, 0x33, 0x2c, 0x2c, 0x31, 0x35, 0x30, 0x33, 0x32, 0x33, 0x2c, + 0x2c, 0x2c, 0x52, 0x2c, 0x56, 0x2a, 0x30, 0x44, 0x0d, 0x0a }); // bad char + TestBadMessage({ 0x24, 0x47, 0x4e, 0x52, 0x4d, 0x43, 0x2c, 0x31, 0x37, 0x34, 0x36, 0x34, 0x34, 0x2e, 0x32, 0x30, + 0x2c, 0x41, 0x2c, 0x34, 0x37, 0x32, 0x34, 0x2e, 0x30, 0x31, 0x38, 0x31, 0x38, 0x2c, 0x4e, 0x2c, 0x30, 0x30, + 0x38, 0x32, 0x37, 0x2e, 0x30, 0x32, 0x32, 0x19, // <-- here + 0x34, 0x2c, 0x45, 0x2c, 0x30, 0x2e, 0x30, 0x31, 0x33, 0x2c, 0x2c, 0x31, 0x35, 0x30, 0x33, 0x32, 0x33, 0x2c, + 0x2c, 0x2c, 0x52, 0x2c, 0x56, 0x2a, 0x30, 0x44, 0x0d, 0x0a }); // bad char + TestBadMessage({ 0x24, 0x47, 0x4e, 0x52, 0x4d, 0x43, 0x2c, 0x31, 0x37, 0x34, 0x36, 0x34, 0x34, 0x2e, 0x32, 0x30, + 0x2c, 0x41, 0x2c, 0x34, 0x37, 0x32, 0x34, 0x2e, 0x30, 0x31, 0x38, 0x31, 0x38, 0x2c, 0x4e, 0x2c, 0x30, 0x30, + 0x38, 0x32, 0x37, 0x2e, 0x30, 0x32, 0x32, 0x81, // <-- here + 0x34, 0x2c, 0x45, 0x2c, 0x30, 0x2e, 0x30, 0x31, 0x33, 0x2c, 0x2c, 0x31, 0x35, 0x30, 0x33, 0x32, 0x33, 0x2c, + 0x2c, 0x2c, 0x52, 0x2c, 0x56, 0x2a, 0x30, 0x44, 0x0d, 0x0a }); // bad char + TestBadMessage({ 0x24, 0x47, 0x4e, 0x52, 0x4d, 0x43, 0x2c, 0x31, 0x37, 0x34, 0x36, 0x34, 0x34, 0x2e, 0x32, 0x30, + 0x2c, 0x41, 0x2c, 0x34, 0x37, 0x32, 0x34, 0x2e, 0x30, 0x31, 0x38, 0x31, 0x38, 0x2c, 0x4e, 0x2c, 0x30, 0x30, + 0x38, 0x32, 0x37, 0x2e, 0x30, 0x32, 0x32, 0x34, 0x34, 0x2c, 0x45, 0x2c, 0x30, 0x2e, 0x30, 0x31, 0x33, 0x2c, + 0x2c, 0x31, 0x35, 0x30, 0x33, 0x32, 0x33, 0x2c, 0x2c, 0x2c, 0x52, 0x2c, 0x56, 0x47, 0x47, 0x47, 0x47, 0x47, + 0x47, 0x47, 0x47, 0x47, 0x47, 0x47, 0x47, 0x47, 0x47, 0x47, 0x47, 0x47, 0x47, 0x47, 0x47, 0x47, 0x47, 0x47, + 0x47, 0x47, 0x47, 0x47, 0x47, 0x47, 0x47, 0x47, 0x47, 0x47, 0x47, 0x47, 0x47, 0x47, 0x47, 0x47, 0x47, 0x47, + 0x47, 0x47, 0x47, 0x47, 0x47, 0x47, 0x47, 0x47, 0x47, 0x47, 0x47, 0x47, 0x47, 0x47, 0x47, 0x47, 0x47, 0x47, + 0x47, 0x47, 0x47, 0x47, 0x47, 0x47, 0x47, 0x47, 0x47, 0x47, 0x47, 0x47, 0x47, 0x47, 0x47, 0x47, 0x47, 0x47, + 0x47, 0x47, 0x47, 0x47, 0x47, 0x47, 0x47, 0x47, 0x47, 0x47, 0x47, 0x47, 0x47, 0x47, 0x47, 0x47, 0x47, 0x47, + 0x47, 0x47, 0x47, 0x47, 0x47, 0x47, 0x47, 0x47, 0x47, 0x47, 0x47, 0x47, 0x47, 0x47, 0x47, 0x47, 0x47, 0x47, + 0x47, 0x47, 0x47, 0x47, 0x47, 0x47, 0x47, 0x47, 0x47, 0x47, 0x47, 0x47, 0x47, 0x47, 0x47, 0x47, 0x47, 0x47, + 0x47, 0x47, 0x47, 0x47, 0x47, 0x47, 0x47, 0x47, 0x47, 0x47, 0x47, 0x47, 0x47, 0x47, 0x47, 0x47, 0x47, 0x47, + 0x47, 0x47, 0x47, 0x47, 0x47, 0x47, 0x47, 0x47, 0x47, 0x47, 0x47, 0x47, 0x47, 0x47, 0x47, 0x47, 0x47, 0x47, + 0x47, 0x47, 0x47, 0x47, 0x47, 0x47, 0x47, 0x47, 0x47, 0x47, 0x47, 0x47, 0x47, 0x47, 0x47, 0x47, 0x47, 0x47, + 0x47, 0x47, 0x47, 0x47, 0x47, 0x47, 0x47, 0x47, 0x47, 0x47, 0x47, 0x47, 0x47, 0x47, 0x47, 0x47, 0x47, 0x47, + 0x47, 0x47, 0x47, 0x47, 0x47, 0x47, 0x47, 0x47, 0x47, 0x47, 0x47, 0x47, 0x47, 0x47, 0x47, 0x47, 0x47, 0x47, + 0x47, 0x47, 0x47, 0x47, 0x47, 0x47, 0x47, 0x47, 0x47, 0x47, 0x47, 0x47, 0x47, 0x47, 0x47, 0x47, 0x47, 0x47, + 0x47, 0x47, 0x47, 0x47, 0x47, 0x47, 0x47, 0x47, 0x47, 0x47, 0x47, 0x47, 0x47, 0x47, 0x47, 0x47, 0x47, 0x47, + 0x47, 0x47, 0x47, 0x47, 0x47, 0x47, 0x47, 0x47, 0x47, 0x47, 0x47, 0x47, 0x47, 0x47, 0x47, 0x47, 0x47, 0x47, + 0x47, 0x47, 0x47, 0x47, 0x47, 0x47, 0x47, 0x47, 0x47, 0x47, 0x47, 0x47, 0x47, 0x47, 0x47, 0x47, 0x47, 0x47, + 0x47, 0x47, 0x47, 0x47, 0x47, 0x47, 0x47, 0x47, 0x47, 0x47, 0x47, 0x47, 0x47, 0x47, 0x47, 0x47, 0x47, 0x47, + 0x47, 0x47, 0x47, 0x47, 0x47, 0x47, 0x47, 0x47, 0x47, 0x47, 0x47, 0x47, 0x47, 0x47, 0x47, 0x47, 0x47, 0x47, + 0x47, 0x47, 0x47, 0x47, 0x47, 0x47, 0x47, 0x47, 0x47, 0x47, 0x47, 0x47, 0x47, 0x47, 0x47, 0x47, 0x47, 0x47, + 0x47, 0x47, 0x47, 0x47, 0x47, 0x47, 0x47, 0x47, 0x47, 0x47, 0x47, 0x47, 0x47, 0x47, 0x47, 0x47, 0x47, 0x47, + 0x47, 0x47, 0x47, 0x47, 0x47, 0x47, 0x47, 0x47, 0x47, 0x47, 0x47, 0x47, 0x47, 0x47, 0x47, 0x47, 0x47, 0x47, + 0x47, 0x47, 0x47, 0x47, 0x47, 0x47, 0x47, 0x47, 0x47, 0x47, 0x47, 0x47, 0x47, 0x47, 0x47, 0x47, 0x47, 0x2a, + 0x30, 0x44, 0x0d, 0x0a }); // too long + TestBadMessage({ 0x24, 0x47, 0x4e, 0x52, 0x4d, 0x43, 0x2c, 0x31, 0x37, 0x34, 0x36, 0x34, 0x34, 0x2e, 0x32, 0x30, + 0x2c, 0x41, 0x2c, 0x34, 0x37, 0x32, 0x34, 0x2e, 0x30, 0x31, 0x38, 0x31, 0x38, 0x2c, 0x4e, 0x2c, 0x30, 0x30, + 0x38, 0x32, 0x37, 0x2e, 0x30, 0x32, 0x32, 0x34, 0x34, 0x2c, 0x45, 0x2c, 0x30, 0x2e, 0x30, 0x31, 0x33, 0x2c, + 0x2c, 0x31, 0x35, 0x30, 0x33, 0x32, 0x33, 0x2c, 0x2c, 0x2c, 0x52, 0x2c, 0x56, 0x2a, 0x30, 0x45, 0x0d, + 0x0a }); // bad CRC +} + +// --------------------------------------------------------------------------------------------------------------------- + +TEST_F(ParserTest, Mixed) +{ + Parser parser; + EXPECT_TRUE( // clang-format off + TestLog(parser, TEST_DATA_MIXED_BIN, { + { "FP_A-ODOMETRY", { 0x24, 0x46, 0x50, 0x2c, 0x4f, 0x44, 0x4f, 0x4d, 0x45, 0x54, 0x52, 0x59, 0x2c, 0x32, 0x2c, 0x32, 0x32, 0x35, 0x33, 0x2c, 0x33, 0x32, 0x33, 0x32, 0x39, 0x39, 0x2e, 0x31, 0x30, 0x30, 0x30, 0x30, 0x30, 0x2c, 0x2c, 0x2c, 0x2c, 0x2c, 0x2c, 0x2c, 0x2c, 0x2c, 0x2c, 0x2c, 0x2c, 0x2c, 0x2c, 0x2c, 0x2c, 0x2c, 0x30, 0x2c, 0x30, 0x2c, 0x38, 0x2c, 0x38, 0x2c, 0x2d, 0x31, 0x2c, 0x2c, 0x2c, 0x2c, 0x2c, 0x2c, 0x2c, 0x2c, 0x2c, 0x2c, 0x2c, 0x2c, 0x2c, 0x2c, 0x2c, 0x2c, 0x2c, 0x2c, 0x2c, 0x66, 0x70, 0x5f, 0x72, 0x65, 0x6c, 0x65, 0x61, 0x73, 0x65, 0x5f, 0x76, 0x72, 0x32, 0x5f, 0x32, 0x2e, 0x36, 0x33, 0x2e, 0x31, 0x5f, 0x32, 0x30, 0x34, 0x2a, 0x37, 0x42, 0x0d, 0x0a } }, + { "NMEA-GN-RMC", { 0x24, 0x47, 0x4e, 0x52, 0x4d, 0x43, 0x2c, 0x31, 0x37, 0x34, 0x36, 0x34, 0x34, 0x2e, 0x32, 0x30, 0x2c, 0x41, 0x2c, 0x34, 0x37, 0x32, 0x34, 0x2e, 0x30, 0x31, 0x38, 0x31, 0x38, 0x2c, 0x4e, 0x2c, 0x30, 0x30, 0x38, 0x32, 0x37, 0x2e, 0x30, 0x32, 0x32, 0x34, 0x34, 0x2c, 0x45, 0x2c, 0x30, 0x2e, 0x30, 0x31, 0x33, 0x2c, 0x2c, 0x31, 0x35, 0x30, 0x33, 0x32, 0x33, 0x2c, 0x2c, 0x2c, 0x52, 0x2c, 0x56, 0x2a, 0x30, 0x44, 0x0d, 0x0a } }, + { "NOV_B-BESTPOS", { 0xaa, 0x44, 0x12, 0x1c, 0x2a, 0x00, 0x00, 0xa0, 0x48, 0x00, 0x00, 0x00, 0x23, 0xb4, 0x83, 0x08, 0x64, 0xdb, 0x68, 0x0c, 0x00, 0x08, 0x00, 0x03, 0xba, 0xcd, 0x19, 0x40, 0x00, 0x00, 0x00, 0x00, 0x38, 0x00, 0x00, 0x00, 0xcf, 0x6a, 0x48, 0x15, 0x4c, 0xb3, 0x47, 0x40, 0xe6, 0xeb, 0x19, 0x6b, 0xb8, 0xe3, 0x20, 0x40, 0x00, 0x00, 0x58, 0x31, 0xd2, 0x84, 0x78, 0x40, 0x66, 0x66, 0x3e, 0x42, 0x3d, 0x00, 0x00, 0x00, 0x85, 0x2d, 0x11, 0x3d, 0xf3, 0xd6, 0x04, 0x3d, 0xc6, 0x57, 0x52, 0x3d, 0x30, 0x00, 0x00, 0x00, 0x00, 0x00, 0x80, 0x3f, 0x00, 0x00, 0x00, 0x00, 0x16, 0x15, 0x15, 0x10, 0x00, 0x21, 0x15, 0x33, 0x3f, 0x6c, 0xbc, 0xfe } }, + { "OTHER", /* random */ { 0xe5, 0x60, 0x12, 0x2f, 0x97, 0x8c, 0x5e, 0x1c, 0x51, 0x01, 0xb8, 0xd1, 0xe2, 0x33, 0x15, 0xed, 0xcd, 0x96, 0x2e, 0x36, 0x66, 0x32, 0x51, 0xf5, 0xa7, 0x6a, 0x40, 0x5e, 0x38, 0x13, 0xd7, 0xf4, 0xba, 0x78, 0xb3, 0x98, 0xce, 0x6c, 0x8f, 0x4e, 0x32, 0x2c } }, + { "RTCM3-TYPE1107", { 0xd3, 0x00, 0x16, 0x45, 0x30, 0x00, 0x4d, 0x10, 0x93, 0xa2, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x1f, 0x9b, 0x2f } }, + { "SPARTN-OCB-GLO", { 0x73, 0x00, 0x10, 0xe3, 0x18, 0xb9, 0xa1, 0x8d, 0x68, 0x5b, 0x1f, 0x88, 0xa0, 0xba, 0xc2, 0x37, 0x43, 0xeb, 0x3f, 0xbe, 0x08, 0xf8, 0x51, 0x7f, 0x3a, 0x9a, 0x78, 0x32, 0x85, 0xc6, 0xe2, 0xd0, 0x7e, 0xee, 0x37, 0xcb, 0x3d, 0x6a, 0x8f, 0xf1, 0x4c, 0x27, 0x43, 0x0d, 0x2a, 0x70, 0xf2, 0x01 } }, + { "UBX-TIM-TP", { 0xb5, 0x62, 0x0d, 0x01, 0x10, 0x00, 0x88, 0xb7, 0x43, 0x13, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0xcd, 0x08, 0x1b, 0x3f, 0xe2, 0xd2 } }, + { "OTHER", /* partial RTCM3 */ { 0xd3, 0x00, 0x16, 0x45, 0x30, 0x00, 0x4d, 0x10, 0x93, 0xa2, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00 } }, + { "FP_A-TF", { 0x24, 0x46, 0x50, 0x2c, 0x54, 0x46, 0x2c, 0x32, 0x2c, 0x32, 0x32, 0x35, 0x33, 0x2c, 0x33, 0x32, 0x33, 0x32, 0x39, 0x39, 0x2e, 0x30, 0x30, 0x30, 0x30, 0x30, 0x30, 0x2c, 0x56, 0x52, 0x54, 0x4b, 0x2c, 0x43, 0x41, 0x4d, 0x2c, 0x2d, 0x30, 0x2e, 0x30, 0x33, 0x34, 0x30, 0x30, 0x2c, 0x30, 0x2e, 0x30, 0x30, 0x32, 0x30, 0x30, 0x2c, 0x2d, 0x30, 0x2e, 0x30, 0x31, 0x36, 0x30, 0x30, 0x2c, 0x2d, 0x30, 0x2e, 0x30, 0x30, 0x30, 0x30, 0x30, 0x30, 0x2c, 0x30, 0x2e, 0x30, 0x30, 0x30, 0x30, 0x30, 0x30, 0x2c, 0x30, 0x2e, 0x30, 0x30, 0x30, 0x30, 0x30, 0x30, 0x2c, 0x31, 0x2e, 0x30, 0x30, 0x30, 0x30, 0x30, 0x30, 0x2a, 0x36, 0x36, 0x0d, 0x0a } }, + { "NMEA-GN-GGA", { 0x24, 0x47, 0x4e, 0x47, 0x47, 0x41, 0x2c, 0x31, 0x37, 0x34, 0x36, 0x34, 0x34, 0x2e, 0x32, 0x30, 0x2c, 0x34, 0x37, 0x32, 0x34, 0x2e, 0x30, 0x31, 0x38, 0x31, 0x38, 0x2c, 0x4e, 0x2c, 0x30, 0x30, 0x38, 0x32, 0x37, 0x2e, 0x30, 0x32, 0x32, 0x34, 0x34, 0x2c, 0x45, 0x2c, 0x34, 0x2c, 0x31, 0x32, 0x2c, 0x30, 0x2e, 0x35, 0x38, 0x2c, 0x34, 0x31, 0x32, 0x2e, 0x31, 0x2c, 0x4d, 0x2c, 0x34, 0x37, 0x2e, 0x33, 0x2c, 0x4d, 0x2c, 0x31, 0x2e, 0x32, 0x2c, 0x30, 0x30, 0x30, 0x30, 0x2a, 0x36, 0x43, 0x0d, 0x0a } }, + { "NOV_B-BESTXYZ", { 0xaa, 0x44, 0x12, 0x1c, 0xf1, 0x00, 0x00, 0xa0, 0x70, 0x00, 0x00, 0x00, 0x23, 0xb4, 0x83, 0x08, 0x64, 0xdb, 0x68, 0x0c, 0x00, 0x08, 0x00, 0x03, 0xcf, 0x44, 0x19, 0x40, 0x00, 0x00, 0x00, 0x00, 0x38, 0x00, 0x00, 0x00, 0x1f, 0x3d, 0xf8, 0xcb, 0x1f, 0x52, 0x50, 0x41, 0x78, 0xc3, 0x4c, 0x3a, 0x76, 0x62, 0x23, 0x41, 0x6f, 0x85, 0xb2, 0x17, 0xda, 0xd2, 0x51, 0x41, 0x16, 0x9c, 0x45, 0x3d, 0x33, 0x55, 0x00, 0x3d, 0xc7, 0xac, 0x25, 0x3d, 0x00, 0x00, 0x00, 0x00, 0x38, 0x00, 0x00, 0x00, 0x44, 0xe5, 0x5d, 0x83, 0x19, 0x93, 0x60, 0x3f, 0xf2, 0x70, 0xb0, 0x6b, 0xcf, 0xcd, 0x58, 0xbf, 0xa0, 0xee, 0x54, 0x82, 0xfd, 0xe1, 0x0c, 0xbf, 0x28, 0x7c, 0xe1, 0x3a, 0xca, 0x65, 0xe9, 0x3a, 0xf8, 0xae, 0xdf, 0x3a, 0x30, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x80, 0x3f, 0x00, 0x00, 0x00, 0x00, 0x16, 0x15, 0x15, 0x10, 0x00, 0x21, 0x15, 0x33, 0x0d, 0xdb, 0x0c, 0xcd } }, + { "RTCM3-TYPE1077", { 0xd3, 0x01, 0x21, 0x43, 0x50, 0x00, 0x4d, 0x10, 0x93, 0xa2, 0x00, 0x00, 0x40, 0xa1, 0xa5, 0x32, 0x80, 0x00, 0x00, 0x00, 0x20, 0x00, 0x80, 0x00, 0x7f, 0xdd, 0xfb, 0xa8, 0xa2, 0x22, 0xa9, 0xa5, 0xa9, 0x25, 0x24, 0xaa, 0x21, 0xaa, 0x29, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x6d, 0x39, 0xaa, 0xad, 0x7f, 0x4a, 0x28, 0x71, 0x1f, 0xd9, 0x2d, 0x00, 0x8f, 0x17, 0x06, 0x7d, 0x6e, 0x01, 0xa8, 0x2d, 0xe1, 0x7c, 0x07, 0x8c, 0x1d, 0x5f, 0xf5, 0x41, 0x8b, 0x07, 0xfe, 0x0f, 0x50, 0x35, 0xdf, 0x85, 0x0a, 0x14, 0xb8, 0xad, 0xe6, 0x6a, 0x5a, 0x7e, 0xa0, 0x41, 0xe2, 0xde, 0x76, 0x1c, 0xa0, 0x62, 0x70, 0x66, 0x16, 0x88, 0x1b, 0x9f, 0xce, 0xde, 0x14, 0xed, 0x6c, 0xbf, 0x60, 0x94, 0xf8, 0x0e, 0xdf, 0x6f, 0x44, 0xfe, 0x1c, 0x77, 0xb1, 0x3b, 0x7c, 0x27, 0xa7, 0xb2, 0xe8, 0x6e, 0x8c, 0x2e, 0x34, 0x19, 0x63, 0x69, 0x4f, 0xff, 0xf7, 0xa0, 0x9e, 0x2c, 0xcf, 0xfd, 0x4c, 0x07, 0x8f, 0xa6, 0x57, 0x61, 0x75, 0x77, 0x84, 0x20, 0xe0, 0x09, 0x5c, 0x3f, 0xff, 0xeb, 0x60, 0x4e, 0x05, 0x5f, 0xf8, 0x93, 0xaf, 0xa4, 0xe5, 0x28, 0x40, 0xa0, 0xa7, 0xa5, 0x52, 0xa0, 0x61, 0x07, 0x78, 0x00, 0x0f, 0x7f, 0xff, 0xf7, 0x50, 0x72, 0xa1, 0x50, 0x18, 0xbe, 0x67, 0xff, 0xf8, 0x37, 0x9f, 0xfc, 0x7f, 0x5b, 0x15, 0xd8, 0x00, 0xe0, 0xca, 0x32, 0xdc, 0xcf, 0x31, 0xc4, 0x80, 0x04, 0xed, 0x41, 0x50, 0xb0, 0xa4, 0xd7, 0x32, 0x00, 0x00, 0x04, 0xd3, 0x39, 0x00, 0x10, 0x33, 0x58, 0x00, 0x04, 0x47, 0xc2, 0x80, 0xbc, 0x2f, 0x0b, 0x82, 0x80, 0x94, 0x1f, 0x0b, 0x42, 0x40, 0x98, 0x2e, 0x0a, 0x82, 0x50, 0x50, 0x1c, 0x0b, 0x42, 0xa0, 0x44, 0x28, 0x09, 0x43, 0x82, 0xe7, 0x0c, 0x80, 0x94, 0x41, 0x38, 0x39, 0x80, 0x73, 0xc1, 0x11, 0x6a, 0x2f, 0x34, 0x7d, 0x87, 0xa5, 0x9e, 0xe6, 0x1f, 0x88, 0x36, 0xaf, 0x6a, 0x88, 0x05, 0x10, 0x63, 0xf4, 0x8c, 0x21, 0x57, 0x41, 0xc5, 0x1c, 0x8d, 0x36, 0xbd, 0x80, 0x91, 0xb2, 0x79 } }, + { "SPARTN-OCB-GPS", { 0x73, 0x00, 0x7a, 0x6a, 0x08, 0xb9, 0xa0, 0x3d, 0xe0, 0x5b, 0x1d, 0x48, 0x92, 0x20, 0xe3, 0x57, 0xa1, 0x89, 0x26, 0x9b, 0xfe, 0x4c, 0x18, 0xf4, 0x14, 0x2e, 0x2c, 0xc1, 0x6c, 0x23, 0xa7, 0x0b, 0x66, 0xfc, 0xc0, 0xc9, 0xcb, 0xa7, 0xc0, 0x18, 0x82, 0xd5, 0x59, 0x4a, 0xda, 0x6e, 0xa3, 0x6b, 0x06, 0xd5, 0xa7, 0x00, 0xd5, 0xcd, 0xd3, 0xb8, 0x98, 0xbb, 0x37, 0x3c, 0x36, 0x6b, 0x13, 0x70, 0xf7, 0xd5, 0x46, 0x11, 0x00, 0x1e, 0xb1, 0x0d, 0x47, 0x1e, 0xcd, 0xdd, 0x8b, 0xb0, 0x40, 0xba, 0xb6, 0x86, 0x5c, 0x4c, 0x25, 0x62, 0xdd, 0xff, 0xdb, 0xee, 0x6c, 0x98, 0xe5, 0xd4, 0xae, 0xf6, 0xb8, 0x5e, 0xf3, 0x3e, 0x9f, 0xa0, 0x6c, 0x1b, 0xbd, 0xec, 0xbb, 0xea, 0x88, 0x34, 0xf3, 0x57, 0x33, 0x9a, 0x4a, 0x29, 0x70, 0x9f, 0x14, 0x99, 0x1d, 0x4f, 0x9e, 0xdd, 0x92, 0x48, 0x70, 0x24, 0x28, 0x5c, 0x1a, 0xb4, 0x65, 0x1c, 0x7d, 0x2f, 0x86, 0x31, 0xd3, 0x3f, 0xa6, 0xf6, 0xa0, 0x43, 0xb0, 0x0b, 0x5f, 0xcc, 0xad, 0xb4, 0xa0, 0xe8, 0xd9, 0xe1, 0x60, 0x19, 0x46, 0xe7, 0xbd, 0x64, 0x2f, 0x09, 0x1a, 0x82, 0xb6, 0x1f, 0x37, 0x20, 0x79, 0xde, 0x64, 0x60, 0x4a, 0x9f, 0x2e, 0x52, 0x6d, 0xa0, 0x20, 0x97, 0xab, 0xb6, 0xd2, 0x57, 0x44, 0xc7, 0xa4, 0xd1, 0x08, 0xf0, 0xd0, 0x3c, 0xe4, 0xc8, 0x9e, 0x75, 0x9a, 0x66, 0xea, 0xd8, 0x78, 0x24, 0x13, 0x7a, 0xd0, 0xd2, 0xab, 0x29, 0x1c, 0xaf, 0x2e, 0x37, 0x94, 0x3b, 0x58, 0x31, 0x58, 0x56, 0xe1, 0x04, 0x45, 0x99, 0x7a, 0xc6, 0x7f, 0x85, 0xe1, 0x91, 0x9a, 0x77, 0x85, 0x5b, 0x6b, 0x3d, 0x2f, 0x55, 0x8c, 0x59, 0xe7, 0x06, 0x7f, 0x32, 0xa4, 0x26, 0x44, 0xb7, 0x44, 0x10, 0x1d, 0xa5, 0xbb, 0xf4, 0x59, 0x00, 0xf6, 0x1b, 0x2a, 0x06, 0xc7 } }, + { "UBX-MON-HW", { 0xb5, 0x62, 0x0a, 0x09, 0x3c, 0x00, 0xc1, 0x81, 0x00, 0x00, 0x1e, 0x00, 0x01, 0x00, 0x00, 0x80, 0x00, 0x00, 0x4e, 0x66, 0x00, 0x00, 0x4f, 0x00, 0x0d, 0x1a, 0x02, 0x01, 0x01, 0x85, 0xbf, 0xff, 0x01, 0x00, 0x3e, 0x06, 0x07, 0x09, 0x08, 0x10, 0xff, 0x12, 0x13, 0x14, 0x15, 0x0e, 0x0a, 0x0b, 0x0f, 0x44, 0x16, 0x39, 0x0e, 0x5a, 0x00, 0x00, 0x00, 0x00, 0xc0, 0x7b, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0xc3, 0x0d } }, + { "OTHER", /* partial UBX */ { 0xb5, 0x62, 0x0a, 0x09, 0x3c, 0x00, 0xc1, 0x81, 0x00, 0x00, 0x1e, 0x00, 0x01, 0x00, 0x00, 0x80, 0x00, 0x00, 0x4e, 0x66, 0x00, 0x00, 0x4f, 0x00, 0x0d, 0x1a, 0x02, 0x01, 0x01, 0x85, 0xbf, 0xff, 0x01, 0x00, 0x3e, 0x06, 0x07, 0x09, 0x08, 0x10 } }, + { "NOV_B-RAWIMUSX", { 0xaa, 0x44, 0x13, 0x28, 0xb6, 0x05, 0x83, 0x08, 0x5b, 0xdb, 0x68, 0x0c, 0x04, 0x3d, 0x83, 0x08, 0x32, 0xac, 0xe2, 0xed, 0x33, 0x6a, 0x09, 0x41, 0x00, 0xfe, 0x27, 0xf8, 0x04, 0x11, 0xd5, 0x09, 0xbc, 0x60, 0x60, 0x00, 0x54, 0xfe, 0x61, 0x00, 0x94, 0x0d, 0x01, 0x00, 0xe0, 0x63, 0x08, 0x00, 0x9c, 0xf5, 0x02, 0x00, 0xea, 0xf1, 0x93, 0x8c } }, + { "RTCM3-TYPE1033", { 0xd3, 0x00, 0x2e, 0x40, 0x90, 0x00, 0x0b, 0x4e, 0x55, 0x4c, 0x4c, 0x41, 0x4e, 0x54, 0x45, 0x4e, 0x4e, 0x41, 0x00, 0x00, 0x15, 0x52, 0x54, 0x4b, 0x42, 0x61, 0x73, 0x65, 0x20, 0x55, 0x62, 0x6c, 0x6f, 0x78, 0x5f, 0x5a, 0x45, 0x44, 0x2d, 0x46, 0x39, 0x50, 0x05, 0x32, 0x2e, 0x33, 0x2e, 0x30, 0x00, 0x7c, 0x92, 0xfb } }, + { "SPARTN-GAD-GAD", { 0x73, 0x04, 0x07, 0xe4, 0x01, 0x4c, 0xd0, 0x5b, 0x1e, 0x48, 0xfe, 0x92, 0xb2, 0xd6, 0xd1, 0xe6, 0x6f, 0x07, 0x30, 0x68, 0x18, 0x8e, 0x48, 0xb3, 0xe1, 0x26, 0x20, 0x4a } }, + { "OTHER", /* random */ { 0x78, 0x47, 0x51, 0xdd, 0xe0, 0xdd, 0x5f, 0xb9, 0x68, 0xfc, 0x77, 0x81, 0x65, 0xb9, 0xfb, 0xcc, 0xb8, 0x7a, 0xe9, 0xf7, 0x42, 0x71, 0xa4, 0x02, 0xef, 0x4c, 0x2a, 0x7e, 0x6d, 0xa0, 0xab, 0x4f, 0xc0, 0xc3, 0x47, 0xd2, 0x0b, 0x02, 0x13, 0xba, 0x38, 0x95, 0x3d, 0xcd, 0x3e, 0x2b, 0x92, 0x3f, 0x06, 0x3e, 0xab, 0xd5, 0x7a, 0x0c, 0xd7, 0x63, 0x17, 0x20, 0x1e, 0xbe, 0xbb, 0x58, 0x29, 0xc5, 0xc0, 0xd1, 0x67, 0xec, 0xf7, 0x64, 0xf4, 0x9c, 0xf6, 0xc1, 0x45, 0xf5, 0xae, 0x5a, 0x80, 0xd0, 0xde, 0xeb, 0x73, 0x32, 0x1e, 0x7b, 0x1a, 0x58, 0x4a, 0xbb, 0x7d, 0x5d, 0x54, 0xf3, 0xc7, 0x7d, 0xdd, 0xa9, 0xcd, 0x4d, 0x08, 0xf8, 0x16, 0x6d, 0xb6, 0x8a, 0x8e, 0xf5, 0x9f, 0xcc, 0x39, 0xb0, 0x8e, 0xa5, 0x77, 0x64, 0x44, 0x93, 0x37, 0x44, 0xc3, 0xc3, 0x5b, 0x41, 0x29, 0x94, 0xde, 0x76, 0x57, 0x95, 0x5e, 0xcd, 0x16, 0x6d, 0x02, 0xa8, 0x18, 0x90, 0xf3, 0x7e, 0x69, 0x34, 0x3a, 0xc2, 0xc3, 0x94, 0x2a, 0xcb, 0x3a, 0x01, 0x43, 0x70, 0xc0, 0x52, 0x0a, 0x00, 0xf2, 0x23, 0x67, 0x68, 0xde, 0x97, 0xf1, 0x3f, 0x8c, 0xbb, 0x19, 0x9f, 0x5b, 0xb4, 0x60, 0x67, 0xb7, 0x61, 0x61, 0x75, 0x33, 0x98, 0xff, 0xf0, 0xee, 0x64, 0x16, 0xcb, 0x29, 0xe8, 0x7f, 0x1d, 0x95, 0x3a, 0xfc, 0xec, 0x34, 0xe3, 0x79, 0xf6, 0x11, 0x98, 0x39, 0x18, 0x35, 0xba, 0xed, 0x14, 0x80, 0x6b, 0x37, 0x43, 0xb4, 0x09, 0x8f, 0x78, 0xe8, 0x31, 0x98, 0x8d, 0x82, 0xf9, 0x0c, 0xc8, 0xb9, 0x64, 0x9e, 0x6d, 0xd9, 0x50, 0x97, 0x94, 0x8e, 0x1a, 0xd7, 0xa2, 0x9d, 0x91, 0x36, 0xcd, 0x67, 0x19, 0xba, 0x32, 0xee, 0x29, 0x96, 0x02, 0x03, 0x87, 0xe7, 0x71, 0xea, 0xff, 0xe2, 0x93, 0x48, 0x32, 0xa6, 0x3b } }, + { "OTHER", /* " */ { 0x73, 0x60, 0x3c, 0xa1, 0x81, 0xc7, 0xaa, 0x2d, 0x1f, 0x2e, 0x5a, 0x43, 0x11, 0x6f, 0x14, 0x1c, 0x6f, 0x9e, 0x04, 0xd4, 0x6b, 0xd3, 0xe9, 0x0d } }, + { "UBX-MON-HW2", { 0xb5, 0x62, 0x0a, 0x0b, 0x1c, 0x00, 0x0c, 0x9e, 0x0c, 0x91, 0x00, 0x8a, 0xa9, 0xb8, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x57, 0x8e } }, + { "SPARTN-HPAC-GLO", { 0x73, 0x02, 0x58, 0xea, 0x18, 0xb9, 0xa1, 0x8f, 0xc0, 0x5b, 0x19, 0x88, 0xda, 0x72, 0xd2, 0x47, 0xb4, 0xf6, 0x0b, 0x58, 0x9a, 0x57, 0x9e, 0x28, 0xb3, 0x29, 0x13, 0xdd, 0xad, 0x03, 0x18, 0x80, 0xbe, 0xdf, 0xcd, 0x67, 0xf9, 0xae, 0x17, 0xbe, 0x9c, 0x53, 0x38, 0xed, 0x41, 0xf0, 0xc2, 0xd7, 0xca, 0x77, 0x31, 0x3d, 0xad, 0xa2, 0xb5, 0x18, 0x53, 0x64, 0xa4, 0xc1, 0xf0, 0x16, 0x53, 0xa5, 0x1e, 0x76, 0xa9, 0x37, 0x97, 0x52, 0x54, 0x47, 0xed, 0x41, 0x73, 0xe1, 0x70, 0x63, 0x89, 0x30, 0x29, 0x77, 0x1a, 0x39, 0x9d, 0x01, 0xb2, 0x02, 0x65, 0x6f, 0x4b, 0x75, 0x6f, 0x01, 0x01, 0xf0, 0x21, 0x5a, 0x4e, 0xc6, 0x2d, 0x2a, 0xa3, 0x9f, 0x3a, 0x08, 0x03, 0x93, 0x2d, 0x1e, 0x82, 0x94, 0xe9, 0x67, 0xb3, 0xdb, 0xd7, 0x7e, 0xbd, 0x49, 0x5a, 0x46, 0xe5, 0x03, 0xe8, 0x9e, 0x7a, 0xee, 0xba, 0x78, 0x6c, 0x12, 0x71, 0xb1, 0xf7, 0xc7, 0xfb, 0xc5, 0x65, 0xa7, 0xa8, 0x83, 0xf8, 0xb9, 0x9b, 0x83, 0x08, 0x29, 0xe6, 0x84, 0xf5, 0x6f, 0x8d, 0xb2, 0x01, 0x74, 0xed, 0x27, 0xc7, 0x57, 0xc9, 0x41, 0x63, 0x8e, 0xb5, 0x7c, 0x6f, 0xfa, 0x1f, 0xfa, 0xee, 0xfc, 0x17, 0xf9, 0x9b, 0x60, 0xa4, 0x16, 0x6c, 0xa1, 0x3e, 0xb7, 0xe2, 0x16, 0xc6, 0xd7, 0x24, 0xd2, 0x06, 0xc6, 0x9a, 0xb2 } }, + { "UBX-NAV-COV", { 0xb5, 0x62, 0x01, 0x36, 0x40, 0x00, 0xb8, 0xfa, 0x43, 0x13, 0x00, 0x01, 0x01, 0x00, 0x32, 0x30, 0x19, 0x40, 0x00, 0x00, 0x80, 0x3f, 0x2e, 0x8e, 0x69, 0x38, 0x88, 0x21, 0xad, 0xb6, 0x08, 0xd0, 0xf5, 0x37, 0x6d, 0x9e, 0x00, 0x38, 0x3b, 0xf0, 0xc3, 0xb5, 0x96, 0x61, 0x52, 0x39, 0xa9, 0x3c, 0x91, 0x3b, 0x58, 0x71, 0xe4, 0xb8, 0xb0, 0xc8, 0xb1, 0x39, 0x32, 0xfd, 0x05, 0x3b, 0x3c, 0xb1, 0x01, 0xb9, 0x3a, 0xe5, 0x8f, 0x3b, 0x47, 0x29 } }, + { "FP_B-MEASUREMENTS", { 0x66, 0x21, 0xd1, 0x07, 0x5c, 0x00, 0x00, 0x00, 0x01, 0x03, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x0a, 0x00, 0x00, 0x00, 0x14, 0x00, 0x00, 0x00, 0xe2, 0xff, 0xff, 0xff, 0x01, 0x01, 0x01, 0x01, 0x01, 0x00, 0x00, 0x00, 0x00, 0x01, 0x0a, 0x00, 0x4e, 0x61, 0xbc, 0x00, 0x0b, 0x00, 0x00, 0x00, 0x15, 0x00, 0x00, 0x00, 0xe3, 0xff, 0xff, 0xff, 0x01, 0x01, 0x01, 0x01, 0x02, 0x00, 0x00, 0x00, 0x00, 0x01, 0x0a, 0x00, 0x4e, 0x61, 0xbc, 0x00, 0x0c, 0x00, 0x00, 0x00, 0x16, 0x00, 0x00, 0x00, 0xe4, 0xff, 0xff, 0xff, 0x01, 0x01, 0x01, 0x01, 0x03, 0x00, 0x00, 0x00, 0x00, 0x01, 0x0a, 0x00, 0x4e, 0x61, 0xbc, 0x00, 0x26, 0x54, 0xaa, 0x34 } } + }, { + { "OTHER", /* partial */ { 0xb5, 0x62, 0x01, 0x35, 0x84, 0x02, 0xb8, 0xfa, 0x43, 0x13, 0x01, 0x35, 0x00, 0x00, 0x00, 0x01, 0x27, 0x07, 0x00, 0x01, 0xf2, 0xff, 0x17, 0x19, 0x00, 0x00, 0x00, 0x07, 0x1a, 0x04, 0x1c, 0x01, 0x00, 0x00, 0x17, 0x19, 0x00, 0x00, 0x00, 0x08, 0x2e, 0x3e, 0x2e, 0x01, 0x02, 0x00, 0x5f, 0x19, 0x32, 0x00, 0x00, 0x0a, 0x31, 0x40, 0x5f, 0x00, 0x05, 0x00, 0x5f, 0x19, 0x32, 0x00, 0x00, 0x0f, 0x00, 0x02, 0x18, 0x00, 0x00, 0x00, 0x11, 0x1a, 0x00, 0x00, 0x00, 0x10, 0x29, 0x23, 0xc1, 0x00, 0xfa, 0xff, 0x5f, 0x19, 0x32, 0x00, 0x00, 0x12, 0x29, 0x0a, 0x46, 0x00, 0xec, 0xff, 0x17, 0x19, 0x00, 0x00, 0x00, 0x15, 0x2b, 0x21, 0x09, 0x01, 0xfd, 0xff, 0x5f, 0x19, 0x32, 0x00, 0x00, 0x17, 0x2c, 0x25, 0x35, 0x00, 0xfa, 0xff, 0x5f, 0x19, 0x32, 0x00, 0x00, 0x1a, 0x09, 0x05, 0xaf, 0x00, 0x00, 0x00, 0x13, 0x19, 0x00, 0x00, 0x00, 0x1b, 0x2f, 0x50, 0x78, 0x00, 0x02, 0x00, 0x5f, 0x19, 0x32, 0x00, 0x00, 0x1e, 0x26, 0x04, 0x3e, 0x01, 0x00, 0x00, 0x17, 0x1a, 0x00, 0x00, 0x00, 0x20, 0x27, 0x0a, 0x83, 0x00, 0x00, 0x00, 0x5f, 0x19, 0x32, 0x00, 0x01, 0x7b, 0x27, 0x1f, 0x96, 0x00, 0x00, 0x00, 0x17, 0x1a, 0x00, 0x00, 0x01, 0x7f, 0x1f, 0x14, 0x7d, 0x00, 0x00, 0x00, 0x07, 0x1a, 0x00, 0x00, 0x01, 0x80, 0x00, 0x02, 0x66, 0x00, 0x00, 0x00, 0x00, 0x12, 0x00, 0x00, 0x01, 0x88, 0x29, 0x23, 0xb9, 0x00, 0x00, 0x00, 0x17, 0x1a, 0x00, 0x00, 0x02, 0x01, 0x2c, 0x2f, 0xec, 0x00, 0x05, 0x00, 0x5f, 0x19, 0x32, 0x00, 0x02, 0x03, 0x25, 0x07, 0x1b, 0x00, 0x00, 0x00, 0x17, 0x19, 0x00, 0x00, 0x02, 0x07, 0x26, 0x10, 0x7f, 0x00, 0xe1, 0xff, 0x1f, 0x19, 0x00, 0x00, 0x02, 0x08 } }, + { "OTHER", /* " */ { 0x29, 0x17, 0x49, 0x00, 0xff, 0xff, 0x5f, 0x19, 0x32, 0x00, 0x02, 0x0d, 0x2a, 0x27, 0x43, 0x00, 0x0b, 0x00, 0x5f, 0x19, 0x32, 0x00, 0x02, 0x15, 0x26, 0x14, 0xbb, 0x00, 0xfb, 0xff, 0x5f, 0x19, 0x32, 0x00, 0x02, 0x1a, 0x2d, 0x4d, 0x39, 0x01, 0x02, 0x00, 0x5f, 0x19, 0x32, 0x00, 0x02, 0x1f, 0x2a, 0x1e, 0x35, 0x01, 0x07, 0x00, 0x5f, 0x19, 0x32, 0x00, 0x02, 0x21, 0x28, 0x1e, 0x08, 0x01, 0x01, 0x00, 0x5f, 0x19, 0x32, 0x00, 0x03, 0x02, 0x00, 0x02, 0x64, 0x00, 0x00, 0x00, 0x10, 0x12, 0x00, 0x00, 0x03, 0x05, 0x00, 0x12, 0x78, 0x00, 0x00, 0x00, 0x10, 0x12, 0x00, 0x00, 0x03, 0x08, 0x20, 0x03, 0x2e, 0x00, 0x00, 0x00, 0x17, 0x1a, 0x00, 0x00, 0x03, 0x0d, 0x25, 0x0e, 0x31, 0x00, 0x07, 0x00, 0x5f, 0x19, 0x32, 0x00, 0x03, 0x13, 0x00, 0x07, 0xb6, 0x00, 0x00, 0x00, 0x10, 0x12, 0x00, 0x00, 0x03, 0x14, 0x2d, 0x28, 0x8f, 0x00, 0xf7, 0xff, 0x1f, 0x19, 0x00, 0x00, 0x03, 0x18, 0x00, 0x01, 0x55, 0x01, 0x00, 0x00, 0x10, 0x12, 0x00, 0x00, 0x03, 0x1a, 0x00, 0x13, 0x2c, 0x01, 0x00, 0x00, 0x10, 0x12, 0x00, 0x00, 0x03, 0x1d, 0x2f, 0x4c, 0x3f, 0x01, 0x03, 0x00, 0x5f, 0x19, 0x32, 0x00, 0x03, 0x1e, 0x2d, 0x2a, 0x60, 0x00, 0xfd, 0xff, 0x5f, 0x19, 0x32, 0x00, 0x03, 0x20, 0x2d, 0x27, 0x43, 0x00, 0x04, 0x00, 0x5f, 0x19, 0x32, 0x00, 0x03, 0x23, 0x27, 0x16, 0x20, 0x01, 0x00, 0x00, 0x27, 0x1a, 0x00, 0x00, 0x03, 0x27, 0x00, 0x03, 0x43, 0x00, 0x00, 0x00, 0x10, 0x12, 0x00, 0x00, 0x03, 0x29, 0x00, 0x04, 0x1c, 0x00, 0x00, 0x00, 0x10, 0x19, 0x00, 0x00, 0x03, 0x2d, 0x28, 0x14, 0xf5, 0x00, 0xf9, 0xff, 0x1f, 0x19, 0x00, 0x00, 0x03, 0x3c, 0x00, 0x04, 0x67, 0x00 } }, + { "OTHER", /* " */ { 0x00, 0x00, 0x10, 0x12, 0x00, 0x00, 0x05, 0x03, 0x00, 0xa5, 0x00, 0x00, 0x00, 0x00, 0x01, 0x00, 0x00, 0x00, 0x06, 0x01, 0x26, 0x15, 0x99, 0x00, 0xea, 0xff, 0x5f, 0x19, 0x32, 0x00, 0x06, 0x07, 0x2b, 0x1b, 0x24, 0x00, 0xf6, 0xff, 0x5f, 0x19, 0x32, 0x00, 0x06, 0x08, 0x2d, 0x2c, 0x5f, 0x00, 0xeb, 0xff, 0x5f, 0x19, 0x32, 0x00, 0x06, 0x0d, 0x1c, 0x0b, 0xd4, 0x00, 0xe1, 0xff, 0x5f, 0x19, 0x12, 0x00, 0x06, 0x0e } }, + })); // clang-format on + + const ParserStats stats = parser.GetStats(); + // clang-format off + EXPECT_EQ(stats.n_msgs_, (uint32_t)27); + EXPECT_EQ(stats.s_msgs_, (uint32_t)2837); + EXPECT_EQ(stats.n_fpa_, (uint32_t)2); + EXPECT_EQ(stats.s_fpa_, (uint32_t)213); + EXPECT_EQ(stats.n_fpb_, (uint32_t)1); + EXPECT_EQ(stats.s_fpb_, (uint32_t)104); + EXPECT_EQ(stats.n_nmea_, (uint32_t)2); + EXPECT_EQ(stats.s_nmea_, (uint32_t)152); + EXPECT_EQ(stats.n_ubx_, (uint32_t)4); + EXPECT_EQ(stats.s_ubx_, (uint32_t)200); + EXPECT_EQ(stats.n_rtcm3_, (uint32_t)3); + EXPECT_EQ(stats.s_rtcm3_, (uint32_t)375); + EXPECT_EQ(stats.n_novb_, (uint32_t)3); + EXPECT_EQ(stats.s_novb_, (uint32_t)304); + EXPECT_EQ(stats.n_spartn_, (uint32_t)4); + EXPECT_EQ(stats.s_spartn_, (uint32_t)527); + EXPECT_EQ(stats.n_other_, (uint32_t)8); + EXPECT_EQ(stats.s_other_, (uint32_t)962); + // clang-format on +} + +// --------------------------------------------------------------------------------------------------------------------- + +TEST_F(ParserTest, EmptyNmeaPayload) +{ + { + Parser parser; + const char* str = "$GPGGA*56\r\n"; + EXPECT_TRUE(parser.Add((const uint8_t*)str, strlen(str))); + ParserMsg msg; + EXPECT_TRUE(parser.Process(msg)); + EXPECT_EQ(msg.name_, "NMEA-GP-GGA"); + } + { + Parser parser; + const char* str = "$FP,VERSION*60\r\n"; + EXPECT_TRUE(parser.Add((const uint8_t*)str, strlen(str))); + ParserMsg msg; + EXPECT_TRUE(parser.Process(msg)); + EXPECT_EQ(msg.name_, "FP_A-VERSION"); + } + { + Parser parser; + const char* str = "$FP,VERSION,*4C\r\n"; + EXPECT_TRUE(parser.Add((const uint8_t*)str, strlen(str))); + ParserMsg msg; + EXPECT_TRUE(parser.Process(msg)); + EXPECT_EQ(msg.name_, "FP_A-VERSION"); + } } /* ****************************************************************************************************************** */ diff --git a/fpsdk_common/test/parser_types_test.cpp b/fpsdk_common/test/parser_types_test.cpp new file mode 100644 index 0000000..9a7d766 --- /dev/null +++ b/fpsdk_common/test/parser_types_test.cpp @@ -0,0 +1,81 @@ +/** + * \verbatim + * ___ ___ + * \ \ / / + * \ \/ / Copyright (c) Fixposition AG (www.fixposition.com) and contributors + * / /\ \ License: see the LICENSE file + * /__/ \__\ + * \endverbatim + * + * @file + * @brief Fixposition SDK: tests for fpsdk::common::parser (types) + */ + +/* LIBC/STL */ +#include +#include +#include + +/* EXTERNAL */ +#include + +/* PACKAGE */ +#include +#include +#include + +namespace { +/* ****************************************************************************************************************** */ +using namespace fpsdk::common::parser; + +TEST(ParserTypesTest, ProtocolStr) +{ + // clang-format off + EXPECT_EQ(std::string(ProtocolStr(Protocol::FP_A)), std::string(PROTOCOL_NAME_FP_A)); + EXPECT_EQ(std::string(ProtocolStr(Protocol::FP_B)), std::string(PROTOCOL_NAME_FP_B)); + EXPECT_EQ(std::string(ProtocolStr(Protocol::NMEA)), std::string(PROTOCOL_NAME_NMEA)); + EXPECT_EQ(std::string(ProtocolStr(Protocol::UBX)), std::string(PROTOCOL_NAME_UBX)); + EXPECT_EQ(std::string(ProtocolStr(Protocol::RTCM3)), std::string(PROTOCOL_NAME_RTCM3)); + EXPECT_EQ(std::string(ProtocolStr(Protocol::UNI_B)), std::string(PROTOCOL_NAME_UNI_B)); + EXPECT_EQ(std::string(ProtocolStr(Protocol::NOV_B)), std::string(PROTOCOL_NAME_NOV_B)); + EXPECT_EQ(std::string(ProtocolStr(Protocol::SPARTN)), std::string(PROTOCOL_NAME_SPARTN)); + EXPECT_EQ(std::string(ProtocolStr(Protocol::OTHER)), std::string(PROTOCOL_NAME_OTHER)); + EXPECT_EQ(std::string(ProtocolStr((Protocol)99)), std::string("?")); + // clang-format on +} + +// --------------------------------------------------------------------------------------------------------------------- + +TEST(ParserTypesTest, StrProtocol) +{ + // clang-format off + EXPECT_EQ(StrProtocol(PROTOCOL_NAME_FP_A), Protocol::FP_A); + EXPECT_EQ(StrProtocol(PROTOCOL_NAME_FP_B), Protocol::FP_B); + EXPECT_EQ(StrProtocol(PROTOCOL_NAME_NMEA), Protocol::NMEA); + EXPECT_EQ(StrProtocol(PROTOCOL_NAME_UBX), Protocol::UBX); + EXPECT_EQ(StrProtocol(PROTOCOL_NAME_RTCM3), Protocol::RTCM3); + EXPECT_EQ(StrProtocol(PROTOCOL_NAME_UNI_B), Protocol::UNI_B); + EXPECT_EQ(StrProtocol(PROTOCOL_NAME_NOV_B), Protocol::NOV_B); + EXPECT_EQ(StrProtocol(PROTOCOL_NAME_SPARTN), Protocol::SPARTN); + EXPECT_EQ(StrProtocol(PROTOCOL_NAME_OTHER), Protocol::OTHER); + EXPECT_EQ(StrProtocol("?"), Protocol::OTHER); + EXPECT_EQ(StrProtocol("UBx"), Protocol::OTHER); + EXPECT_EQ(StrProtocol("UBXX"), Protocol::OTHER); + // clang-format on +} + +/* ****************************************************************************************************************** */ +} // namespace + +int main(int argc, char** argv) +{ + testing::InitGoogleTest(&argc, argv); + auto level = fpsdk::common::logging::LoggingLevel::WARNING; + for (int ix = 0; ix < argc; ix++) { + if ((argv[ix][0] == '-') && argv[ix][1] == 'v') { + level++; + } + } + fpsdk::common::logging::LoggingSetParams(level); + return RUN_ALL_TESTS(); +} diff --git a/fpsdk_common/test/parser_ubx_test.cpp b/fpsdk_common/test/parser_ubx_test.cpp new file mode 100644 index 0000000..88f820c --- /dev/null +++ b/fpsdk_common/test/parser_ubx_test.cpp @@ -0,0 +1,170 @@ +/** + * \verbatim + * ___ ___ + * \ \ / / + * \ \/ / Copyright (c) Fixposition AG (www.fixposition.com) and contributors + * / /\ \ License: see the LICENSE file + * /__/ \__\ + * \endverbatim + * + * @file + * @brief Fixposition SDK: tests for fpsdk::common::parser::ubx + */ + +/* LIBC/STL */ +#include +#include + +/* EXTERNAL */ +#include + +/* PACKAGE */ +#include +#include +#include + +namespace { +/* ****************************************************************************************************************** */ +using namespace fpsdk::common::parser; +using namespace fpsdk::common::parser::ubx; + +TEST(ParserUbxTest, Macros) +{ + const uint8_t msg[] = { UBX_SYNC_1, UBX_SYNC_2, 0x12, 0x34, 0x00, 0x00, 0x55, 0x55 }; + ASSERT_EQ(UbxClsId(msg), 0x12); + ASSERT_EQ(UbxMsgId(msg), 0x34); +} + +// --------------------------------------------------------------------------------------------------------------------- + +TEST(ParserUbxTest, UbxGetMessageName) +{ + // Known message + { + const uint8_t msg[] = { UBX_SYNC_1, UBX_SYNC_2, UBX_NAV_CLSID, UBX_NAV_PVT_MSGID, 0x00, 0x00, 0x00, 0x00 }; + char str[100]; + EXPECT_TRUE(UbxGetMessageName(str, sizeof(str), msg, sizeof(msg))); + EXPECT_EQ(std::string(str), std::string("UBX-NAV-PVT")); + } + + // Known class, but unknown message + { + const uint8_t msg[] = { UBX_SYNC_1, UBX_SYNC_2, UBX_NAV_CLSID, 0x99, 0x00, 0x00, 0x00, 0x00 }; + char str[100]; + EXPECT_TRUE(UbxGetMessageName(str, sizeof(str), msg, sizeof(msg))); + EXPECT_EQ(std::string(str), std::string("UBX-NAV-99")); + } + + // Completely unknown message + { + const uint8_t msg[] = { UBX_SYNC_1, UBX_SYNC_2, 0x99, 0x99, 0x00, 0x00, 0x00, 0x00 }; + char str[100]; + EXPECT_TRUE(UbxGetMessageName(str, sizeof(str), msg, sizeof(msg))); + EXPECT_EQ(std::string(str), std::string("UBX-99-99")); + } + + // Bad arguments + { + const uint8_t msg[] = { UBX_SYNC_1, UBX_SYNC_2, UBX_NAV_CLSID, UBX_NAV_PVT_MSGID, 0x00, 0x00, 0x00, 0x00 }; + char str[100]; + EXPECT_FALSE(UbxGetMessageName(str, 0, msg, sizeof(msg))); + EXPECT_FALSE(UbxGetMessageName(NULL, 10, msg, sizeof(msg))); + EXPECT_FALSE(UbxGetMessageName(NULL, 0, msg, sizeof(msg))); + EXPECT_FALSE(UbxGetMessageName(str, sizeof(str), msg, 0)); + EXPECT_FALSE(UbxGetMessageName(str, sizeof(str), msg, UBX_FRAME_SIZE - 1)); + EXPECT_FALSE(UbxGetMessageName(str, sizeof(str), NULL, sizeof(msg))); + } + + // Too small string is cut + { + const uint8_t msg[] = { UBX_SYNC_1, UBX_SYNC_2, UBX_NAV_CLSID, UBX_NAV_PVT_MSGID, 0x00, 0x00, 0x00, 0x00 }; + char str[10]; + EXPECT_FALSE(UbxGetMessageName(str, sizeof(str), msg, sizeof(msg))); + EXPECT_EQ(std::string(str), std::string("UBX-NAV-P")); + } +} + +// --------------------------------------------------------------------------------------------------------------------- + +TEST(ParserUbxTest, UbxMakeMessage) +{ + for (const int payload_size : + { 0, 1, 2, 3, 4, 5, 6, 7, 8, 100, 200, 500, 1000, 2000, (int)(MAX_UBX_SIZE - UBX_FRAME_SIZE) }) { + // Create payload with this many bytes of data + std::vector payload; + for (int ix = 0; ix < payload_size; ix++) { + payload.push_back((uint8_t)(ix + 1)); + } + + // We expect a message of this size + const int msg_size = payload_size + UBX_FRAME_SIZE; + + // Create message + std::vector msg; + EXPECT_TRUE(UbxMakeMessage(msg, 0xaa, 0x55, payload)); + EXPECT_EQ((int)msg.size(), msg_size); + + // Create message using "raw" API + std::vector msg2; + EXPECT_TRUE(UbxMakeMessage(msg2, 0xaa, 0x55, payload.data(), (int)payload.size())); + EXPECT_EQ(msg.size(), msg2.size()); + EXPECT_EQ(std::memcmp(msg.data(), msg2.data(), msg.size()), 0); + + // Run it through the parser and check that it is still the same + Parser parser; + parser.Add(msg); + ParserMsg parser_message; + EXPECT_TRUE(parser.Process(parser_message)); + EXPECT_EQ(parser_message.data_.size(), UBX_FRAME_SIZE + payload.size()); + EXPECT_EQ(std::string(parser_message.name_), std::string("UBX-AA-55")); + // Payload should be the same + EXPECT_TRUE(std::memcmp(payload.data(), &parser_message.data_[UBX_HEAD_SIZE], payload.size()) == 0); + + // There should be nothing left in the parser + EXPECT_FALSE(parser.Flush(parser_message)); + } + + // Too large (by one byte) + { + std::vector payload(MAX_UBX_SIZE - UBX_FRAME_SIZE + 1); + std::vector msg; + EXPECT_FALSE(UbxMakeMessage(msg, 0xaa, 0x55, payload)); + EXPECT_EQ(msg.size(), (std::size_t)0); + EXPECT_FALSE(UbxMakeMessage(msg, 0xaa, 0x55, payload.data(), payload.size())); + EXPECT_EQ(msg.size(), (std::size_t)0); + } + + // Combinations of arguments + { + const uint8_t payload[] = { 0x55, 0x55 }; + std::vector msg; + // These are okay: + EXPECT_TRUE(UbxMakeMessage(msg, 0xaa, 0x55, payload, 0)); + EXPECT_EQ(msg.size(), (std::size_t)UBX_FRAME_SIZE); + msg.clear(); + EXPECT_TRUE(UbxMakeMessage(msg, 0xaa, 0x55, NULL, 0)); + EXPECT_EQ(msg.size(), (std::size_t)UBX_FRAME_SIZE); + // But these are bad: + msg.clear(); + EXPECT_EQ(msg.size(), (std::size_t)0); + EXPECT_FALSE(UbxMakeMessage(msg, 0xaa, 0x55, NULL, 1)); + EXPECT_EQ(msg.size(), (std::size_t)0); + EXPECT_EQ(msg.size(), (std::size_t)0); + } +} + +/* ****************************************************************************************************************** */ +} // namespace + +int main(int argc, char** argv) +{ + testing::InitGoogleTest(&argc, argv); + auto level = fpsdk::common::logging::LoggingLevel::WARNING; + for (int ix = 0; ix < argc; ix++) { + if ((argv[ix][0] == '-') && argv[ix][1] == 'v') { + level++; + } + } + fpsdk::common::logging::LoggingSetParams(level); + return RUN_ALL_TESTS(); +} diff --git a/fpsdk_common/test/parser_unib_test.cpp b/fpsdk_common/test/parser_unib_test.cpp new file mode 100644 index 0000000..77acaa5 --- /dev/null +++ b/fpsdk_common/test/parser_unib_test.cpp @@ -0,0 +1,113 @@ +/** + * \verbatim + * ___ ___ + * \ \ / / + * \ \/ / Copyright (c) Fixposition AG (www.fixposition.com) and contributors + * / /\ \ License: see the LICENSE file + * /__/ \__\ + * \endverbatim + * + * @file + * @brief Fixposition SDK: tests for fpsdk::common::parser::unib + */ + +/* LIBC/STL */ +#include +#include + +/* EXTERNAL */ +#include + +/* PACKAGE */ +#include +#include + +namespace { +/* ****************************************************************************************************************** */ +using namespace fpsdk::common::parser::unib; + +TEST(ParserUnibTest, Macros) +{ + { + const uint8_t msg[] = { 0x55, 0x55, 0x55, 0x55, 0x34, 0x12, 0xaa, 0xaa, 0xaa }; + ASSERT_EQ(UnibMsgId(msg), 0x1234); + } + + { + const uint8_t msg[] = { 0x55, 0x55, 0x55, 0x55, 0x55, 0x55, 0x34, 0x12, 0xaa, 0xaa, 0xaa }; + ASSERT_EQ(UnibMsgSize(msg), 0x1234); + } + { + const uint8_t msg[] = { 0x55, 0x55, 0x55, 0x55, 0x55, 0x55, 0x55, 0x55, 0x55, 0x55, 0x55, 0x55, 0x55, 0x55, + 0x55, 0x55, 0x55, 0x55, 0x55, 0x55, 0x12, 0xaa, 0xaa, 0xaa }; + ASSERT_EQ(UNI_B_MSGVER(msg), 0x12); + } +} + +// --------------------------------------------------------------------------------------------------------------------- + +TEST(ParserUnibTest, UnibGetMessageName) +{ + // Known message + { + const uint8_t msg[] = { // clang-format off + UNI_B_SYNC_1, UNI_B_SYNC_2, UNI_B_SYNC_3, 0x00, + (uint8_t)(UNI_B_VERSION_MSGID & 0xff), (uint8_t)((UNI_B_VERSION_MSGID >> 8) & 0xff), + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00 }; // clang-format on + char str[100]; + EXPECT_TRUE(UnibGetMessageName(str, sizeof(str), msg, sizeof(msg))); + EXPECT_EQ(std::string(str), std::string("UNI_B-VERSION")); + } + + // Unknown message + { + const uint8_t msg[] = { // clang-format off + UNI_B_SYNC_1, UNI_B_SYNC_2, UNI_B_SYNC_3, 0x00, + 0x34, 0x12, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00 }; // clang-format on + char str[100]; + EXPECT_TRUE(UnibGetMessageName(str, sizeof(str), msg, sizeof(msg))); + EXPECT_EQ(std::string(str), std::string("UNI_B-MSG04660")); + } + + // Bad arguments + { + const uint8_t msg[] = { // clang-format off + UNI_B_SYNC_1, UNI_B_SYNC_2, UNI_B_SYNC_3, 0x00, + 0x34, 0x12, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00 }; // clang-format on + char str[100]; + EXPECT_FALSE(UnibGetMessageName(str, 0, msg, sizeof(msg))); + EXPECT_FALSE(UnibGetMessageName(NULL, 10, msg, sizeof(msg))); + EXPECT_FALSE(UnibGetMessageName(NULL, 0, msg, sizeof(msg))); + EXPECT_FALSE(UnibGetMessageName(str, sizeof(str), msg, 0)); + EXPECT_FALSE(UnibGetMessageName(str, sizeof(str), msg, 5)); + EXPECT_FALSE(UnibGetMessageName(str, sizeof(str), NULL, sizeof(msg))); + } + // Too small string is cut + { + const uint8_t msg[] = { // clang-format off + UNI_B_SYNC_1, UNI_B_SYNC_2, UNI_B_SYNC_3, 0x00, + (uint8_t)(UNI_B_VERSION_MSGID & 0xff), (uint8_t)((UNI_B_VERSION_MSGID >> 8) & 0xff), + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00 }; // clang-format on + char str[10]; + EXPECT_FALSE(UnibGetMessageName(str, sizeof(str), msg, sizeof(msg))); + EXPECT_EQ(std::string(str), std::string("UNI_B-VER")); + } +} + +/* ****************************************************************************************************************** */ +} // namespace + +int main(int argc, char** argv) +{ + testing::InitGoogleTest(&argc, argv); + auto level = fpsdk::common::logging::LoggingLevel::WARNING; + for (int ix = 0; ix < argc; ix++) { + if ((argv[ix][0] == '-') && argv[ix][1] == 'v') { + level++; + } + } + fpsdk::common::logging::LoggingSetParams(level); + return RUN_ALL_TESTS(); +} diff --git a/fpsdk_common/test/string_test.cpp b/fpsdk_common/test/string_test.cpp index fa504a5..c43b79c 100644 --- a/fpsdk_common/test/string_test.cpp +++ b/fpsdk_common/test/string_test.cpp @@ -12,6 +12,7 @@ */ /* LIBC/STL */ +#include /* EXTERNAL */ #include @@ -255,6 +256,8 @@ TEST(StringTest, StrToValue_int8) } } +// --------------------------------------------------------------------------------------------------------------------- + TEST(StringTest, StrToValue_uint8) { // clang-format off @@ -289,6 +292,8 @@ TEST(StringTest, StrToValue_uint8) } } +// --------------------------------------------------------------------------------------------------------------------- + TEST(StringTest, StrToValue_int16) { // clang-format off @@ -323,6 +328,8 @@ TEST(StringTest, StrToValue_int16) } } +// --------------------------------------------------------------------------------------------------------------------- + TEST(StringTest, StrToValue_uint16) { // clang-format off @@ -357,6 +364,8 @@ TEST(StringTest, StrToValue_uint16) } } +// --------------------------------------------------------------------------------------------------------------------- + TEST(StringTest, StrToValue_int32) { // clang-format off @@ -391,6 +400,8 @@ TEST(StringTest, StrToValue_int32) } } +// --------------------------------------------------------------------------------------------------------------------- + TEST(StringTest, StrToValue_uint32) { // clang-format off @@ -425,6 +436,8 @@ TEST(StringTest, StrToValue_uint32) } } +// --------------------------------------------------------------------------------------------------------------------- + TEST(StringTest, StrToValue_int64) { // clang-format off @@ -461,6 +474,8 @@ TEST(StringTest, StrToValue_int64) } } +// --------------------------------------------------------------------------------------------------------------------- + TEST(StringTest, StrToValue_uint64) { // clang-format off @@ -496,6 +511,8 @@ TEST(StringTest, StrToValue_uint64) } } +// --------------------------------------------------------------------------------------------------------------------- + TEST(StringTest, StrToValue_float) { // clang-format off @@ -527,6 +544,8 @@ TEST(StringTest, StrToValue_float) } } +// --------------------------------------------------------------------------------------------------------------------- + TEST(StringTest, StrToValue_double) { // clang-format off @@ -558,6 +577,8 @@ TEST(StringTest, StrToValue_double) } } +// --------------------------------------------------------------------------------------------------------------------- + TEST(StringTest, StrToUpper) { EXPECT_EQ(StrToUpper("foobar 123#%^"), std::string("FOOBAR 123#%^")); @@ -565,6 +586,8 @@ TEST(StringTest, StrToUpper) EXPECT_EQ(StrToUpper("FooBar 123#%^"), std::string("FOOBAR 123#%^")); } +// --------------------------------------------------------------------------------------------------------------------- + TEST(StringTest, StrToLower) { EXPECT_EQ(StrToLower("foobar 123#%^"), std::string("foobar 123#%^")); @@ -572,6 +595,27 @@ TEST(StringTest, StrToLower) EXPECT_EQ(StrToLower("FooBar 123#%^"), std::string("foobar 123#%^")); } +// --------------------------------------------------------------------------------------------------------------------- + +TEST(StringTest, StrError) +{ + { + const auto str = StrError(EAGAIN); // "Resource temporarily unavailable (11, EAGAIN)" + DEBUG("str: %s", str.c_str()); + EXPECT_FALSE(str.empty()); + } + { + const auto str = StrError(0); // "Success (0, 0)" + DEBUG("str: %s", str.c_str()); + EXPECT_FALSE(str.empty()); + } + { + const auto str = StrError(-2); // "Unknown error (-2, ?)" + DEBUG("str: %s", str.c_str()); + EXPECT_FALSE(str.empty()); + } +} + /* ****************************************************************************************************************** */ } // namespace diff --git a/fpsdk_common/test/time_test.cpp b/fpsdk_common/test/time_test.cpp index 357b6c4..071b89a 100644 --- a/fpsdk_common/test/time_test.cpp +++ b/fpsdk_common/test/time_test.cpp @@ -1068,7 +1068,7 @@ TEST(TimeTest, Time_Clock) if (adjtimex(&tx) == TIME_OK) { tx_tai = tx.tai; } else { - WARNING("adjtimex() fail: %s", strerror(errno)); + WARNING("adjtimex() fail: %s", fpsdk::common::string::StrError(errno).c_str()); } DEBUG("tx_tai=%d", tx_tai); diff --git a/Doxyfile b/fpsdk_doc/Doxyfile similarity index 99% rename from Doxyfile rename to fpsdk_doc/Doxyfile index a033cee..ff69018 100644 --- a/Doxyfile +++ b/fpsdk_doc/Doxyfile @@ -1033,7 +1033,8 @@ EXCLUDE_SYMBOLS = EXAMPLE_PATH = fpsdk_doc \ fpsdk_common fpsdk_common/doc \ - fpsdk_ros1 fpsdk_ros1/doc \ + fpsdk_ros1 fpsdk_ros1/doc fpsdk_ros1/msg \ + fpsdk_ros2 fpsdk_ros2/doc \ fpsdk_apps fpsdk_apps/doc # If the value of the EXAMPLE_PATH tag contains directories, you can use the @@ -2346,7 +2347,7 @@ MACRO_EXPANSION = NO # The default value is: NO. # This tag requires that the tag ENABLE_PREPROCESSING is set to YES. -EXPAND_ONLY_PREDEF = NO +EXPAND_ONLY_PREDEF = YES # If the SEARCH_INCLUDES tag is set to YES, the include files in the # INCLUDE_PATH will be searched if a #include is found. diff --git a/fpsdk_doc/README.md b/fpsdk_doc/README.md index ef80970..6e38bdd 100644 --- a/fpsdk_doc/README.md +++ b/fpsdk_doc/README.md @@ -18,16 +18,17 @@ For building the libraries and apps: -- **Linux**, GCC (C++-17), glibc, cmake, bash, etc. (tested with Ubuntu 22.04, Ubuntu 24.04 and Debian Bookworm) -- yaml-cpp (≥ ?, tested with 0.6.2) -- boost (≥ ?, tested with 1.71.0) -- zlib1g (≥ ?, tested with 1.2.11) -- Eigen3 (≥ ?, tested with 3.3.7) +- **Linux**, GCC (C++-17), glibc, cmake, bash, etc. (tested with Ubuntu 20.04/22.04/24.04 and Debian Bookworm) +- boost (≥ 1.71.0, tested with 1.71.0, 1.74.1, 1.83.0) +- curl (≥ 7.68.0, tested with 7.68.0, 7.88.1, 8.5.0) +- Eigen3 (≥ 3.3.7, tested with 3.3.7, 3.4.0) +- yaml-cpp (≥ 0.6.2, tested with 0.6.2, 0.7.0, 0.8.0) +- zlib1g (≥ 1.2.11, tested with 1.2.11, 1.2.13, 1.3) - PROJ (*) (≥ 9.?.?, tested with 9.4.1) -- ROS1 (*) (Noetic, tested with Noetic), or -- ROS2 (*) (Humble, tested with Humble and Jazzy) +- ROS1 (*) (Noetic), or +- ROS2 (*) (Humble or Jazzy) -(*) Optional dependencies. Without these some functionality will be unavailable in the built libraries and apps. +(*) Optional dependencies. Without these some functionality in the libraries and apps is unavailable (compiled out). For development additionally: diff --git a/fpsdk_doc/fpsdk-overview.drawio.svg b/fpsdk_doc/fpsdk-overview.drawio.svg index 16f2b13..1f2dd5c 100644 --- a/fpsdk_doc/fpsdk-overview.drawio.svg +++ b/fpsdk_doc/fpsdk-overview.drawio.svg @@ -1,4 +1,4 @@ - + @@ -76,12 +76,12 @@ - - + + -
+

@@ -95,17 +95,17 @@

- + yaml-cpp - - + + -
+

@@ -119,7 +119,7 @@

- + roscpp etc. @@ -148,12 +148,12 @@ - - + + -
+

@@ -167,7 +167,7 @@

- + zlib1g @@ -214,7 +214,7 @@ - +
@@ -266,7 +266,7 @@ - +
@@ -300,22 +300,6 @@ - - - -
-
-
- coming soon -
-
-
-
- - coming soon - -
-
@@ -364,12 +348,12 @@ - - + + -
+

@@ -383,17 +367,17 @@

- + curl - - + + -
+

@@ -407,17 +391,17 @@

- + Eigen - - + + -
+

@@ -431,7 +415,7 @@

- + GTest @@ -458,12 +442,12 @@ - - + + -
+

@@ -477,7 +461,7 @@

- + rclcpp etc. @@ -485,7 +469,7 @@ -
+
optional @@ -493,7 +477,7 @@
- + optional @@ -501,7 +485,7 @@ -
+
optional @@ -509,7 +493,7 @@
- + optional @@ -548,23 +532,23 @@ - +
- sometimes... + coming soon
- sometimes... + coming soon
- +
@@ -628,11 +612,11 @@ - + -
+
utils @@ -640,12 +624,12 @@
- + utils - + @@ -664,11 +648,11 @@ - + -
+
path @@ -676,17 +660,17 @@
- + path - - + + -
+
math @@ -694,12 +678,12 @@
- + math - + @@ -718,11 +702,11 @@ - + -
+
fpl @@ -730,17 +714,17 @@
- + fpl - - + + -
+
logging @@ -748,17 +732,17 @@
- + logging - - + + -
+
string @@ -766,17 +750,17 @@
- + string - - + + -
+
stream @@ -784,16 +768,16 @@
- + stream - - + + -
+
coming soon @@ -801,7 +785,7 @@
- + coming soon @@ -865,11 +849,11 @@ - + -
+
yaml @@ -877,17 +861,17 @@
- + yaml - - + + -
+
utils @@ -895,19 +879,19 @@
- + utils - - + + -
-
+
+

@@ -943,63 +927,126 @@ - - - t - - - + -

+
- thread + parser
- - thread + + parser - - + -
+
+
+
+ optional +
+
+
+ + + optional + + + + + + +
+
+
+ optional +
+
+
+
+ + optional + +
+
+ + + +
+
+
+ Noetic +
+
+
+
+ + Noetic + +
+
+ + + +
+
+
+ Humble, +
+ Jazzy +
+
+
+
+ + Humble,... + +
+
+ + + + +
- parser + msgs
- - parser + + msgs
- - + + + -
-
-
- coming soon +
+
+
+ thread
- - coming soon + + thread + diff --git a/fpsdk_ros1/CMakeLists.txt b/fpsdk_ros1/CMakeLists.txt index 63e4314..1423cf2 100644 --- a/fpsdk_ros1/CMakeLists.txt +++ b/fpsdk_ros1/CMakeLists.txt @@ -67,6 +67,7 @@ message(STATUS "fpsdk: FP_ROS1_LIBRARIES=${FP_ROS1_LIBRARIES}") file(GLOB MSG_FILES RELATIVE ${CMAKE_CURRENT_SOURCE_DIR} msg/*.msg) +# /opt/ros/noetic/share/genmsg/cmake/genmsg-extras.cmake add_message_files(DIRECTORY ${CMAKE_CURRENT_SOURCE_DIR} FILES ${MSG_FILES}) generate_messages(LANGS gencpp DEPENDENCIES std_msgs) @@ -76,7 +77,7 @@ generate_messages(LANGS gencpp DEPENDENCIES std_msgs) file(GLOB CPP_FILES src/*.cpp) add_library(${PROJECT_NAME} SHARED ${CPP_FILES}) -#add_dependencies(${PROJECT_NAME} ${PROJECT_NAME}_generate_messages) +add_dependencies(${PROJECT_NAME} ${PROJECT_NAME}_generate_messages) target_include_directories(${PROJECT_NAME} PUBLIC @@ -170,6 +171,7 @@ install( include(../fpsdk_common/cmake/testing.cmake) add_gtest(TARGET bagwriter_test SOURCES test/bagwriter_test.cpp LINK_LIBS ${PROJECT_NAME}) +add_gtest(TARGET msgs_test SOURCES test/msgs_test.cpp LINK_LIBS ${PROJECT_NAME}) add_gtest(TARGET utils_test SOURCES test/utils_test.cpp LINK_LIBS ${PROJECT_NAME}) diff --git a/fpsdk_ros1/README.md b/fpsdk_ros1/README.md index 3333b63..3c6e86f 100644 --- a/fpsdk_ros1/README.md +++ b/fpsdk_ros1/README.md @@ -6,7 +6,7 @@ This library contains various ROS1 functionality. This is used for example by th --- ## Dependencies -- [Fixposition SDK dependencies](../README.md#dependencies) +- [Fixposition SDK dependencies](../fpsdk_docs/README.md#dependencies) - [fpsdk_common](../fpsdk_common/README.md) - This *does* need ROS (Noetic) diff --git a/fpsdk_ros1/doc/doc.hpp b/fpsdk_ros1/doc/doc.hpp index 9c4e02e..33caa79 100644 --- a/fpsdk_ros1/doc/doc.hpp +++ b/fpsdk_ros1/doc/doc.hpp @@ -32,6 +32,7 @@ namespace ros1 { @section FPSDK_ROS1_MODULES Modules - @subpage FPSDK_ROS1_BAGWRITER + - @subpage FPSDK_ROS1_MSGS - @subpage FPSDK_ROS1_UTILS @section FPSDK_ROS1_LICENSE License diff --git a/fpsdk_ros1/include/fpsdk_ros1/msgs.hpp b/fpsdk_ros1/include/fpsdk_ros1/msgs.hpp new file mode 100644 index 0000000..ec3ad6c --- /dev/null +++ b/fpsdk_ros1/include/fpsdk_ros1/msgs.hpp @@ -0,0 +1,66 @@ +/** + * \verbatim + * ___ ___ + * \ \ / / + * \ \/ / Copyright (c) Fixposition AG + * / /\ \ License: see the LICENSE file + * /__/ \__\ + * \endverbatim + * + * @file + * @brief Fixposition SDK: ROS1 messages + * + * @page FPSDK_ROS1_MSGS ROS1 messages + * + * **API**: fpsdk_ros1/msgs.hpp and fpsdk::ros1::msgs + * + */ +#ifndef __FPSDK_ROS1_MSGS_HPP__ +#define __FPSDK_ROS1_MSGS_HPP__ + +/* LIBC/STL */ + +/* EXTERNAL */ + +/* Fixposition SDK */ + +/* PACKAGE */ +#pragma GCC diagnostic push +#pragma GCC diagnostic ignored "-Wpedantic" +#pragma GCC diagnostic ignored "-Wunused-parameter" +#pragma GCC diagnostic ignored "-Wshadow" +#include +#pragma GCC diagnostic pop + +namespace fpsdk { +namespace ros1 { +/** + * @brief ROS1 messages + */ +namespace msgs { +/* ****************************************************************************************************************** */ + +/** + * @name ParserMsg + * + * @include{lineno} ParserMsg.msg + * + * @{ + */ + +//! ROS message (instance) similar to fpsdk::common::parser::ParserMsg +using ParserMsg = fpsdk_ros1::ParserMsg; + +//! ROS message (shared pointer) similar to fpsdk::common::parser::ParserMsg +using ParserMsgPtr = fpsdk_ros1::ParserMsgPtr; + +//! ROS message (shared const pointer) similar to fpsdk::common::parser::ParserMsg +using ParserMsgConstPtr = fpsdk_ros1::ParserMsgConstPtr; + +///@} + +/* ****************************************************************************************************************** */ +} // namespace msgs +} // namespace ros1 +} // namespace fpsdk +#endif // __FPSDK_ROS1_MSGS_HPP__ diff --git a/fpsdk_ros1/msg/ParserMsg.msg b/fpsdk_ros1/msg/ParserMsg.msg index 942ffef..e7045e2 100644 --- a/fpsdk_ros1/msg/ParserMsg.msg +++ b/fpsdk_ros1/msg/ParserMsg.msg @@ -1,3 +1,9 @@ +# ___ ___ +# \ \ / / +# \ \/ / Copyright (c) Fixposition AG (www.fixposition.com) and contributors +# / /\ \ License: see the LICENSE file +# /__/ \__\ +# # Similar to a fpsdk::common::parser::ParserMsg time stamp # Timestamp of message reception time diff --git a/fpsdk_ros1/test/msgs_test.cpp b/fpsdk_ros1/test/msgs_test.cpp new file mode 100644 index 0000000..4f06408 --- /dev/null +++ b/fpsdk_ros1/test/msgs_test.cpp @@ -0,0 +1,55 @@ +/** + * \verbatim + * ___ ___ + * \ \ / / + * \ \/ / Copyright (c) Fixposition AG (www.fixposition.com) and contributors + * / /\ \ License: see the LICENSE file + * /__/ \__\ + * \endverbatim + * + * @file + * @brief Fixposition SDK: tests for fpsdk_ros1 messages + */ + +/* LIBC/STL */ + +/* EXTERNAL */ +#include +#include + +/* PACKAGE */ +#include +#include + +namespace { +/* ****************************************************************************************************************** */ + +// Checks that some of the messages didn't change. If we change the message definition, we change the MD5 sum of the +// message and make it binary incompatible. I.e. we cannot use the message from old bags (using the old .msg) with the +// changed .msg. In Python this is not a problem (as long no existing field is changed), but in c++ instantiating the +// message is compiled-in and not dynamic (as in Python). Note that changing the comments in a .msg file does not change +// the MD5 sum. Neither does changing the type names ("data type" in ROS speak) if done consistently (e.g. rename all +// fpsdk_ros1/Foo to fpsdk_ros1/Bar in all .msg). However, changing name of the field does change the MD5 sum, and so +// does changing the order, adding or removing fields. +TEST(MsgsTest, MustNeverChange) +{ + // clang-format off + EXPECT_EQ(std::string(ros::message_traits::md5sum()), "9122cb2e555052fd41731dc8fc43888d"); + // clang-format on +} + +/* ****************************************************************************************************************** */ +} // namespace + +int main(int argc, char** argv) +{ + testing::InitGoogleTest(&argc, argv); + auto level = fpsdk::common::logging::LoggingLevel::WARNING; + for (int ix = 0; ix < argc; ix++) { + if ((argv[ix][0] == '-') && argv[ix][1] == 'v') { + level++; + } + } + fpsdk::common::logging::LoggingSetParams(level); + return RUN_ALL_TESTS(); +} diff --git a/fpsdk_ros2/README.md b/fpsdk_ros2/README.md index a2d1212..07ddcf5 100644 --- a/fpsdk_ros2/README.md +++ b/fpsdk_ros2/README.md @@ -6,7 +6,7 @@ This library contains various ROS2 functionality. This is used for example by th --- ## Dependencies -- [Fixposition SDK dependencies](../README.md#dependencies) +- [Fixposition SDK dependencies](../fpsdk_docs/README.md#dependencies) - [fpsdk_common](../fpsdk_common/README.md) - This *does* need ROS (Humble, Jazzy) diff --git a/ros1_fpsdk_demo/launch/node.launch b/ros1_fpsdk_demo/launch/node.launch index 9e3cd6d..d0157aa 100644 --- a/ros1_fpsdk_demo/launch/node.launch +++ b/ros1_fpsdk_demo/launch/node.launch @@ -3,6 +3,6 @@ - +